diff --git a/README.md b/README.md
index 68585ce266..f4571778b2 100644
--- a/README.md
+++ b/README.md
@@ -1,6 +1,6 @@
# MoveIt! Tutorials
-This repo is automatically built by the ROS build farm and its output is hosted here: http://docs.ros.org/kinetic/api/moveit_tutorials/html/
+This repository is automatically built by the ROS build farm and its output is hosted here: http://docs.ros.org/kinetic/api/moveit_tutorials/html/
The tutorials use the [reStructuredText](http://www.sphinx-doc.org/en/stable/rest.html) format commonly used in the Sphinx "Python Documentation Generator". This unfortunately differs from the common Markdown format.
diff --git a/doc/benchmarking/benchmarking_tutorial.rst b/doc/benchmarking/benchmarking_tutorial.rst
index f598c6e9f2..8356a9c18f 100644
--- a/doc/benchmarking/benchmarking_tutorial.rst
+++ b/doc/benchmarking/benchmarking_tutorial.rst
@@ -3,7 +3,7 @@ Benchmarking
.. note:: This is the new benchmarking method only available in ROS Kinetic, onward.
-.. note:: To use this benchmarking method, you will need to download and install the ROS Warehouse plugin. Currently this is not available from debians and requires a source install for at least some aspects. For source instructions, see `this page `_
+.. note:: To use this benchmarking method, you will need to download and install the ROS Warehouse plugin. Currently this is not available from Debians and requires a source install for at least some aspects. For source instructions, see `this page `_
The `benchmarking package `_ provides methods to benchmark motion planning algorithms and aggregate/plot statistics using the OMPL Planner Arena.
The example below demonstrates how the benchmarking can be run for a Fanuc M-10iA.
@@ -38,7 +38,7 @@ To run:
Viewing Results
---------------
-The benchmarks are executed and many interesting parameters are aggregated and written to a logfile. A script (``moveit_benchmark_statistics.py``) is supplied to parse this data and plot the statistics.
+The benchmarks are executed and many interesting parameters are aggregated and written to a log file. A script (``moveit_benchmark_statistics.py``) is supplied to parse this data and plot the statistics.
Run: ::
diff --git a/doc/chomp_interface/chomp_interface_tutorial.rst b/doc/chomp_interface/chomp_interface_tutorial.rst
index 47085ada95..3159b91a51 100644
--- a/doc/chomp_interface/chomp_interface_tutorial.rst
+++ b/doc/chomp_interface/chomp_interface_tutorial.rst
@@ -15,17 +15,17 @@ Once you have this package simply run::
Assumptions:
------------
- 1. You have the latest version of moveit installed. On ROS kinetic you may need to build it from source.
- 2. You have a moveit configuration package for your robot already. For example, if you have a Kinova Jaco arm, it's probably called "jaco_moveit_config". This is typically built using the Moveit Setup Assistant.
- 3. Lets assume that you are using the **jaco** manipulator. And hence, the moveit config package is *jaco_moveit_config*.
+ 1. You have the latest version of MoveIt! installed. On ROS kinetic you may need to build it from source.
+ 2. You have a MoveIt! configuration package for your robot already. For example, if you have a Kinova Jaco arm, it's probably called "jaco_moveit_config". This is typically built using the MoveIt! Setup Assistant.
+ 3. Lets assume that you are using the **Jaco** manipulator. And hence, the MoveIt! config package is *jaco_moveit_config*.
Using CHOMP with your own robot
-------------------------------
-1. Simply download `chomp_planning_pipeline.launch.xml `_ file into the launch directory of your moveit config package. So into the *jaco_moveit_config/launch* directory.
+1. Simply download `chomp_planning_pipeline.launch.xml `_ file into the launch directory of your MoveIt! config package. So into the *jaco_moveit_config/launch* directory.
2. Adjust the line to
-3. Download `chomp_planning.yaml `_ file into the config directory of your moveit config package. So into the *jaco_moveit_config/config* directory.
+3. Download `chomp_planning.yaml `_ file into the config directory of your MoveIt! config package. So into the *jaco_moveit_config/config* directory.
4. Copy the *demo.launch* file to *demo_chomp.launch*. Note that this file is also in the launch directory of the *jaco_moveit_config* package.
5. Find the lines where *move_group.launch* is included and change it to: ::
diff --git a/doc/collision_contact/collision_contact_tutorial.rst b/doc/collision_contact/collision_contact_tutorial.rst
index f00a8a0eaa..59ba2af987 100644
--- a/doc/collision_contact/collision_contact_tutorial.rst
+++ b/doc/collision_contact/collision_contact_tutorial.rst
@@ -1,6 +1,6 @@
Collision Contact
=================
-This section walks you through C++ code which allows you to see collision contact points between the robot, itself, and the world as you move and interact with the robot’s arm in Rviz.
+This section walks you through C++ code which allows you to see collision contact points between the robot, itself, and the world as you move and interact with the robot’s arm in RViz.
Getting Started
---------------
@@ -28,14 +28,14 @@ The :code:`InteractiveRobot` class uses the :code:`IMarker` class which maintain
Interacting
-----------
-In Rviz you will see two sets of Red/Green/Blue interactive marker arrows. Drag these around with the mouse.
+In RViz you will see two sets of Red/Green/Blue interactive marker arrows. Drag these around with the mouse.
Move the right arm so it is in contact with the left arm. You will see magenta spheres marking the contact points.
If you do not see the magenta spheres be sure that you added the MarkerArray display with interactive_robot_marray topic as described above. Also be sure to set RobotAlpha to 0.3 (or some other value less than 1) so the robot is transparent and the spheres can be seen.
Move the right arm so it is in contact with the yellow cube (you may also move the yellow cube). You will see magenta spheres marking the contact points.
Relevant Code
-------------
-The entire code can be seen :codedir:`here ` in the moveit_tutorials Github project. Libraries used can be found :codedir:`here `. A lot of information necessary for understanding how this demo works is left out to keep this tutorial focused on collision contacts. To understand this demo fully, it is highly recommended that you read through the source code.
+The entire code can be seen :codedir:`here ` in the moveit_tutorials GitHub project. Libraries used can be found :codedir:`here `. A lot of information necessary for understanding how this demo works is left out to keep this tutorial focused on collision contacts. To understand this demo fully, it is highly recommended that you read through the source code.
.. tutorial-formatter:: ./src/collision_contact_tutorial.cpp
diff --git a/doc/collision_contact/launch/collision_contact_tutorial.launch b/doc/collision_contact/launch/collision_contact_tutorial.launch
index 0556f901a1..529bc8f81b 100644
--- a/doc/collision_contact/launch/collision_contact_tutorial.launch
+++ b/doc/collision_contact/launch/collision_contact_tutorial.launch
@@ -6,7 +6,7 @@
-
+
diff --git a/doc/custom_constraint_samplers/custom_constraint_samplers_tutorial.rst b/doc/custom_constraint_samplers/custom_constraint_samplers_tutorial.rst
index 815e9d2b4c..a9cf0050fc 100644
--- a/doc/custom_constraint_samplers/custom_constraint_samplers_tutorial.rst
+++ b/doc/custom_constraint_samplers/custom_constraint_samplers_tutorial.rst
@@ -6,7 +6,7 @@ Overview
Some planning problems require more complex or custom constraint
samplers for more difficult planning problems. This document explains
-how to creat a custom motion planning constraint sampler for use
+how to create a custom motion planning constraint sampler for use
with MoveIt!.
Pre-requisites
@@ -15,7 +15,7 @@ Pre-requisites
Creating a constraint sampler
-----------------------------
-* Create a ROBOT_moveit_plugins package and within that a subfolder for your YOURROBOT_constraint_sampler plugin.
+* Create a ROBOT_moveit_plugins package and within that a sub-folder for your YOURROBOT_constraint_sampler plugin.
Modify the template provided by hrp2jsk_moveit_plugins/hrp2jsk_moveit_constraint_sampler_plugin
* In your ROBOT_moveit_config/launch/move_group.launch file, within the , add
the parameter:
diff --git a/doc/fake_controller_manager/fake_controller_manager_tutorial.rst b/doc/fake_controller_manager/fake_controller_manager_tutorial.rst
index b64fb575f1..8a7a2e170e 100644
--- a/doc/fake_controller_manager/fake_controller_manager_tutorial.rst
+++ b/doc/fake_controller_manager/fake_controller_manager_tutorial.rst
@@ -2,14 +2,14 @@ Fake Controller Manager
=================================
MoveIt! comes with a series of fake trajectory controllers to be used in simulation.
-For example, the ``demo.launch`` generated by MoveIt's setup assistant, employs fake controllers for nice visualization in rviz.
+For example, the ``demo.launch`` generated by MoveIt's setup assistant, employs fake controllers for nice visualization in RViz.
For configuration, edit the file ``config/fake_controllers.yaml``, and adjust the desired controller type.
The following controllers are available:
* **interpolate**: perform smooth interpolation between via points - the default for visualization
* **via points**: traverse via points, w/o interpolation in between - useful for visual debugging
-* **last point**: warp directly to the last point of the trajectory - fastest method for offline benchmarking
+* **last point**: warp directly to the last point of the trajectory - fastest method for off-line benchmarking
YAML file examples
------------------
diff --git a/doc/ikfast/ikfast_tutorial.rst b/doc/ikfast/ikfast_tutorial.rst
index dda8bb6bab..4176220032 100644
--- a/doc/ikfast/ikfast_tutorial.rst
+++ b/doc/ikfast/ikfast_tutorial.rst
@@ -12,7 +12,7 @@ MoveIt! IKFast
---------------
MoveIt! IKFast is a tool that generates a IKFast kinematics plugin for MoveIt using OpenRAVE generated cpp files.
-This tutorial will step you through setting up your robot to utilize the power of IKFast. MoveIt! IKFast is tested on ROS Kinetic with Catkin using OpenRAVE 0.8 with a 6dof and 7dof robot arm manipulator.
+This tutorial will step you through setting up your robot to utilize the power of IKFast. MoveIt! IKFast is tested on ROS Kinetic with Catkin using OpenRAVE 0.8 with a 6DOF and 7DOF robot arm manipulator.
While it works in theory, currently the IKFast plugin generator tool does not work with >7 degree of freedom arms.
Getting Started
@@ -21,7 +21,7 @@ If you haven't already done so, make sure you've completed the steps in `Getting
You should have MoveIt! configuration package for your robot that was created by using the `Setup Assistant <../setup_assistant/setup_assistant_tutorial.html>`_
-Installing OpenRAVE on Ubuntu 16.04 is tricky. Here are 2 blog posts that give slightly different recepies for installing OpenRAVE.
+Installing OpenRAVE on Ubuntu 16.04 is tricky. Here are 2 blog posts that give slightly different recipes for installing OpenRAVE.
* `Stéphane Caron's Installing OpenRAVE on Ubuntu 16.04 `_
* `Francisco Suárez-Ruiz's Robotics Workstation Setup in Ubuntu 16.04 `_
@@ -30,7 +30,7 @@ Make sure you have these programs installed: ::
sudo apt-get install cmake g++ git ipython minizip python-dev python-h5py python-numpy python-scipy qt4-dev-tools
-You may also need the followng libraries: ::
+You may also need the following libraries: ::
sudo apt-get install libassimp-dev libavcodec-dev libavformat-dev libavformat-dev libboost-all-dev libboost-date-time-dev libbullet-dev libfaac-dev libglew-dev libgsm1-dev liblapack-dev liblog4cxx-dev libmpfr-dev libode-dev libogg-dev libpcrecpp0v5 libpcre3-dev libqhull-dev libqt4-dev libsoqt-dev-common libsoqt4-dev libswscale-dev libswscale-dev libvorbis-dev libx264-dev libxml2-dev libxvidcore-dev
@@ -87,7 +87,7 @@ Note: you have to set: ::
Working commit numbers 5cfc7444... confirmed for Ubuntu 14.04 and 9c79ea26... confirmed for Ubuntu 16.04, according to Stéphane Caron.
-**Please report your results with this on** `this Github repo. `_
+**Please report your results with this on** `this GitHub repository. `_
Create Collada File For Use With OpenRAVE
@@ -117,13 +117,13 @@ Once you have your robot in URDF format, you can convert it to Collada (.dae) fi
rosrun collada_urdf urdf_to_collada "$MYROBOT_NAME".urdf "$MYROBOT_NAME".dae
-Often floating point issues arrise in converting a URDF file to Collada file, so a script has been created to round all the numbers down to x decimal places in your .dae file. Its probably best if you skip this step initially and see if IKFast can generate a solution with your default values, but if the generator takes longer than, say, an hour, try the following: ::
+Often floating point issues arise in converting a URDF file to Collada file, so a script has been created to round all the numbers down to x decimal places in your .dae file. Its probably best if you skip this step initially and see if IKFast can generate a solution with your default values, but if the generator takes longer than, say, an hour, try the following: ::
export IKFAST_PRECISION="5"
- cp "$MYROBOT_NAME".dae "$MYROBOT_NAME".bakup.dae # create a backup of your full precision dae.
+ cp "$MYROBOT_NAME".dae "$MYROBOT_NAME".backup.dae # create a backup of your full precision dae.
rosrun moveit_kinematics round_collada_numbers.py "$MYROBOT_NAME".dae "$MYROBOT_NAME".dae "$IKFAST_PRECISION"
-From experience we recommend 5 decimal places, but if the OpenRAVE ikfast generator takes to long to find a solution, lowering the number of decimal places should help.
+From experience we recommend 5 decimal places, but if the OpenRAVE IKFast generator takes to long to find a solution, lowering the number of decimal places should help.
To see the links in your newly generated Collada file
@@ -190,18 +190,18 @@ Set the base link and EEF link to the desired index::
export BASE_LINK="0"
export EEF_LINK="8"
-If you have a 7 DOF arm you will need ot specify a free link::
+If you have a 7 DOF arm you will need to specify a free link::
export FREE_INDEX="1"
Generate IK Solver
^^^^^^^^^^^^^^^^^^
-To generate the IK solution between the manipulator's base and tool frames for a 6 dof arm, use the following command format. We recommend you name the output ikfast61\_"$PLANNING_GROUP".cpp: ::
+To generate the IK solution between the manipulator's base and tool frames for a 6DOF arm, use the following command format. We recommend you name the output ikfast61\_"$PLANNING_GROUP".cpp: ::
export IKFAST_OUTPUT_PATH=`pwd`/ikfast61_"$PLANNING_GROUP".cpp
-For a 6 dof arm: ::
+For a 6DOF arm: ::
python `openrave-config --python-dir`/openravepy/_openravepy_/ikfast.py --robot="$MYROBOT_NAME".dae --iktype=transform6d --baselink="$BASE_LINK" --eelink="$EEF_LINK" --savefile="$IKFAST_OUTPUT_PATH"
@@ -254,7 +254,7 @@ Edit these parts: ::
Test the Plugin
^^^^^^^^^^^^^^^
-Use the MoveIt Rviz Motion Planning Plugin and use the interactive markers to see if correct IK Solutions are found.
+Use the MoveIt RViz Motion Planning Plugin and use the interactive markers to see if correct IK Solutions are found.
Updating the Plugin
-------------------
diff --git a/doc/joystick_control_teleoperation/joystick_control_teleoperation_tutorial.rst b/doc/joystick_control_teleoperation/joystick_control_teleoperation_tutorial.rst
index c9a70595fb..5105f84c8e 100644
--- a/doc/joystick_control_teleoperation/joystick_control_teleoperation_tutorial.rst
+++ b/doc/joystick_control_teleoperation/joystick_control_teleoperation_tutorial.rst
@@ -8,13 +8,13 @@ If you haven't already done so, make sure you've completed the steps in `Getting
Run
---
-Startup regular MoveIt! planning node with Rviz (for example demo.launch)
+Startup regular MoveIt! planning node with RViz (for example demo.launch)
Make sure you have the dependencies installed: ::
sudo apt-get install ros-kinetic-joy
-In the Motion Planning plugin of Rviz, enable "Allow External Comm." checkbox in the "Planning" tab. Enable the 'Query Goal State' robot display in the MoveIt! Motion Planning Plugins's 'Planning Request' section.
+In the Motion Planning plugin of RViz, enable "Allow External Comm." checkbox in the "Planning" tab. Enable the 'Query Goal State' robot display in the MoveIt! Motion Planning Plugins' 'Planning Request' section.
Now launch the joystick control launch file specific to your robot. If you are missing this file, first re-run the MoveIt! Setup Assistant using the latest version of the Setup Assistant: ::
@@ -51,6 +51,6 @@ execute circle B 2
Debugging
---------
-Add "Pose" to rviz Displays and subscribe to ``/joy_pose`` in order to see the output from joystick.
+Add "Pose" to RViz Displays and subscribe to ``/joy_pose`` in order to see the output from joystick.
Note that only planning groups that have IK solvers for all their End Effector parent groups will work.
diff --git a/doc/kinematic_model/kinematic_model_tutorial.rst b/doc/kinematic_model/kinematic_model_tutorial.rst
index aa20a0602d..f4a1abb55e 100644
--- a/doc/kinematic_model/kinematic_model_tutorial.rst
+++ b/doc/kinematic_model/kinematic_model_tutorial.rst
@@ -12,7 +12,7 @@ The :moveit_core:`RobotModel` and :moveit_core:`RobotState` classes are the core
The :moveit_core:`RobotModel` class contains the relationships between all links and joints including their joint limit properties as loaded from the URDF. The RobotModel also separates the robot's links and joints into planning groups defined in the SRDF. A separate tutorial on the URDF and SRDF can be found here: `URDF and SRDF Tutorial <../urdf_srdf/urdf_srdf_tutorial.html>`_
-The :moveit_core:`RobotState` contains information about the robot at a snapshot in time, storing vectors of joint positions and optionally velocities and accelerations that can be used to obtain kinmatic information about the robot that depends on it's current state such as the Jacobian of an end effector.
+The :moveit_core:`RobotState` contains information about the robot at a snapshot in time, storing vectors of joint positions and optionally velocities and accelerations that can be used to obtain kinematic information about the robot that depends on it's current state such as the Jacobian of an end effector.
RobotState also contains helper functions for setting the arm location based on the end effector location (Cartesian pose) and for computing Cartesian trajectories.
@@ -81,14 +81,14 @@ The expected output will be in the following form. The numbers will not match si
The Entire Code
---------------
-The entire code can be seen :codedir:`here in the MoveIt! Github project`.
+The entire code can be seen :codedir:`here in the MoveIt! GitHub project`.
.. tutorial-formatter:: ./src/kinematic_model_tutorial.cpp
The Launch File
^^^^^^^^^^^^^^^
To run the code, you will need a launch file that does two things:
- * Loads the Panda URDF and SRDF onto the param server, and
+ * Loads the Panda URDF and SRDF onto the parameter server, and
* Puts the kinematics_solver configuration generated by the MoveIt! Setup Assistant onto the ROS parameter server in the namespace of the node that instantiates the classes in this tutorial.
.. literalinclude:: ./launch/kinematic_model_tutorial.launch
\ No newline at end of file
diff --git a/doc/kinematics_configuration/kinematics_configuration_tutorial.rst b/doc/kinematics_configuration/kinematics_configuration_tutorial.rst
index 7f97b8dab2..4b45df73a0 100644
--- a/doc/kinematics_configuration/kinematics_configuration_tutorial.rst
+++ b/doc/kinematics_configuration/kinematics_configuration_tutorial.rst
@@ -6,7 +6,7 @@ In this section, we will examine some of the parameters for configuring kinemati
The kinematics.yaml file
------------------------
-The kinematics.yaml file generated by the MoveIt! Setup Assistant is the primary configuration file for kinematics for MoveIt!. You can see an entire example file for the Panda robot in the `panda_moveit_config Github project `_: ::
+The kinematics.yaml file generated by the MoveIt! Setup Assistant is the primary configuration file for kinematics for MoveIt!. You can see an entire example file for the Panda robot in the `panda_moveit_config GitHub project `_: ::
panda_arm:
kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin
diff --git a/doc/motion_planning_api/motion_planning_api_tutorial.rst b/doc/motion_planning_api/motion_planning_api_tutorial.rst
index 874a0a686b..15580a4375 100644
--- a/doc/motion_planning_api/motion_planning_api_tutorial.rst
+++ b/doc/motion_planning_api/motion_planning_api_tutorial.rst
@@ -11,13 +11,13 @@ If you haven't already done so, make sure you've completed the steps in `Getting
The entire code
---------------
-The entire code can be seen :codedir:`here in the moveit_tutorials github project`.
+The entire code can be seen :codedir:`here in the moveit_tutorials GitHub project`.
.. tutorial-formatter:: ./src/motion_planning_api_tutorial.cpp
The launch file
---------------
-The entire launch file is :codedir:`here ` on github. All the code in this tutorial can be compiled and run from the moveit_tutorials package.
+The entire launch file is :codedir:`here ` on GitHub. All the code in this tutorial can be compiled and run from the moveit_tutorials package.
Running the code
----------------
@@ -31,7 +31,7 @@ Roslaunch the launch file to run the code directly from moveit_tutorials::
Expected Output
---------------
-In Rviz, we should be able to see four trajectories being replayed eventually:
+In RViz, we should be able to see four trajectories being replayed eventually:
1. The robot moves its arm to the first pose goal,
diff --git a/doc/motion_planning_api/src/motion_planning_api_tutorial.cpp b/doc/motion_planning_api/src/motion_planning_api_tutorial.cpp
index 2ceb19b187..3b5a9aed49 100644
--- a/doc/motion_planning_api/src/motion_planning_api_tutorial.cpp
+++ b/doc/motion_planning_api/src/motion_planning_api_tutorial.cpp
@@ -82,7 +82,7 @@ int main(int argc, char** argv)
std::string planner_plugin_name;
// We will get the name of planning plugin we want to load
- // from the ROS param server, and then load the planner
+ // from the ROS parameter server, and then load the planner
// making sure to catch all exceptions.
if (!node_handle.getParam("planning_plugin", planner_plugin_name))
ROS_FATAL_STREAM("Could not find planner plugin name");
diff --git a/doc/motion_planning_pipeline/motion_planning_pipeline_tutorial.rst b/doc/motion_planning_pipeline/motion_planning_pipeline_tutorial.rst
index 0bcb1feab3..7092a117fe 100644
--- a/doc/motion_planning_pipeline/motion_planning_pipeline_tutorial.rst
+++ b/doc/motion_planning_pipeline/motion_planning_pipeline_tutorial.rst
@@ -16,13 +16,13 @@ If you haven't already done so, make sure you've completed the steps in `Getting
The entire code
---------------
-The entire code can be seen :codedir:`here in the MoveIt! Github project`.
+The entire code can be seen :codedir:`here in the MoveIt! GitHub project`.
.. tutorial-formatter:: ./src/motion_planning_pipeline_tutorial.cpp
The launch file
---------------
-The entire launch file is :codedir:`here ` 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 :codedir:`here ` 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
----------------
@@ -36,7 +36,7 @@ Roslaunch the launch file to run the code directly from moveit_tutorials: ::
Expected Output
---------------
-In Rviz, we should be able to see three trajectories being replayed eventually:
+In RViz, we should be able to see three trajectories being replayed eventually:
1. The robot moves its right arm to the pose goal in front of it,
2. The robot moves its right arm to the joint goal to the side,
diff --git a/doc/motion_planning_pipeline/src/motion_planning_pipeline_tutorial.cpp b/doc/motion_planning_pipeline/src/motion_planning_pipeline_tutorial.cpp
index 34713708d5..e8d6a8fe46 100644
--- a/doc/motion_planning_pipeline/src/motion_planning_pipeline_tutorial.cpp
+++ b/doc/motion_planning_pipeline/src/motion_planning_pipeline_tutorial.cpp
@@ -74,7 +74,7 @@ int main(int argc, char** argv)
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
+ // object, which will use the ROS parameter server
// to determine the set of request adapters and the
// planning plugin to use
planning_pipeline::PlanningPipelinePtr planning_pipeline(
diff --git a/doc/move_group_interface/move_group_interface_tutorial.rst b/doc/move_group_interface/move_group_interface_tutorial.rst
index 87ad1454e7..5da9ec1acb 100644
--- a/doc/move_group_interface/move_group_interface_tutorial.rst
+++ b/doc/move_group_interface/move_group_interface_tutorial.rst
@@ -17,7 +17,7 @@ Open two shells and make sure you have re-sourced the setup files in both of the
source ~/ws_moveit/devel/setup.bash
-In the first shell start Rviz and wait for everything to finish loading: ::
+In the first shell start RViz and wait for everything to finish loading: ::
roslaunch panda_moveit_config demo.launch
@@ -25,15 +25,15 @@ In the second shell, run the launch file: ::
roslaunch moveit_tutorials move_group_interface_tutorial.launch
-After a short moment, the Rviz window should appear and look similar to the one at the top of this page. To progress through each demo step either press the **Next** button in the **RvizVisualToolsGui** pannel at the bottom of the screen or select **Key Tool** in the **Tools** pannel at the top of the screen and then press **N** on your keyboard while Rviz is focused.
+After a short moment, the RViz window should appear and look similar to the one at the top of this page. To progress through each demo step either press the **Next** button in the **RvizVisualToolsGui** pannel at the bottom of the screen or select **Key Tool** in the **Tools** pannel at the top of the screen and then press **N** on your keyboard while RViz is focused.
Expected Output
---------------
-See the `YouTube video `_ at the top of this tutorial for expected output. In Rviz, we should be able to see the following:
+See the `YouTube video `_ at the top of this tutorial for expected output. In RViz, we should be able to see the following:
1. The robot moves its arm to the pose goal to its front.
2. The robot moves its arm to the joint goal at its side.
3. The robot moves its arm back to a new pose goal while maintaining the end-effector level.
- 4. The robot moves its arm along the desired cartesian path (a triangle up+forward, left, down+back).
+ 4. The robot moves its arm along the desired Cartesian path (a triangle up+forward, left, down+back).
5. A box object is added into the environment to the right of the arm.
|B|
@@ -46,7 +46,7 @@ See the `YouTube video `_ at the top of this tutor
The Entire Code
---------------
-The entire code can be seen :codedir:`here in the MoveIt! Github project`. Next we step through the code piece by piece to explain its functionality.
+The entire code can be seen :codedir:`here in the MoveIt! GitHub project`. Next we step through the code piece by piece to explain its functionality.
.. tutorial-formatter:: ./src/move_group_interface_tutorial.cpp
diff --git a/doc/move_group_interface/src/move_group_interface_tutorial.cpp b/doc/move_group_interface/src/move_group_interface_tutorial.cpp
index b68011388c..a1085ddbbf 100644
--- a/doc/move_group_interface/src/move_group_interface_tutorial.cpp
+++ b/doc/move_group_interface/src/move_group_interface_tutorial.cpp
@@ -78,21 +78,21 @@ int main(int argc, char **argv)
// ^^^^^^^^^^^^^
//
// The package MoveItVisualTools provides many capabilties for visualizing objects, robots,
- // and trajectories in Rviz as well as debugging tools such as step-by-step introspection of a script
+ // and trajectories in RViz as well as debugging tools such as step-by-step introspection of a script
namespace rvt = rviz_visual_tools;
moveit_visual_tools::MoveItVisualTools visual_tools("panda_link0");
visual_tools.deleteAllMarkers();
// Remote control is an introspection tool that allows users to step through a high level script
- // via buttons and keyboard shortcuts in Rviz
+ // via buttons and keyboard shortcuts in RViz
visual_tools.loadRemoteControl();
- // Rviz provides many types of markers, in this demo we will use text, cylinders, and spheres
+ // RViz provides many types of markers, in this demo we will use text, cylinders, and spheres
Eigen::Affine3d text_pose = Eigen::Affine3d::Identity();
text_pose.translation().z() = 1.75;
visual_tools.publishText(text_pose, "MoveGroupInterface Demo", rvt::WHITE, rvt::XLARGE);
- // Batch publishing is used to reduce the number of messages being sent to Rviz for large visualizations
+ // Batch publishing is used to reduce the number of messages being sent to RViz for large visualizations
visual_tools.trigger();
// Getting Basic Information
@@ -130,7 +130,7 @@ int main(int argc, char **argv)
// Visualizing plans
// ^^^^^^^^^^^^^^^^^
- // We can also visualize the plan as a line with markers in Rviz.
+ // We can also visualize the plan as a line with markers in RViz.
ROS_INFO_NAMED("tutorial", "Visualizing plan 1 as trajectory line");
visual_tools.publishAxisLabeled(target_pose1, "pose1");
visual_tools.publishText(text_pose, "Pose Goal", rvt::WHITE, rvt::XLARGE);
@@ -173,7 +173,7 @@ int main(int argc, char **argv)
success = (move_group.plan(my_plan) == moveit::planning_interface::MoveItErrorCode::SUCCESS);
ROS_INFO_NAMED("tutorial", "Visualizing plan 2 (joint space goal) %s", success ? "" : "FAILED");
- // Visualize the plan in Rviz
+ // Visualize the plan in RViz
visual_tools.deleteAllMarkers();
visual_tools.publishText(text_pose, "Joint Space Goal", rvt::WHITE, rvt::XLARGE);
visual_tools.publishTrajectoryLine(my_plan.trajectory_, joint_model_group);
@@ -224,7 +224,7 @@ int main(int argc, char **argv)
success = (move_group.plan(my_plan) == moveit::planning_interface::MoveItErrorCode::SUCCESS);
ROS_INFO_NAMED("tutorial", "Visualizing plan 3 (constraints) %s", success ? "" : "FAILED");
- // Visualize the plan in Rviz
+ // Visualize the plan in RViz
visual_tools.deleteAllMarkers();
visual_tools.publishAxisLabeled(start_pose2, "start");
visual_tools.publishAxisLabeled(target_pose1, "goal");
@@ -238,7 +238,7 @@ int main(int argc, char **argv)
// Cartesian Paths
// ^^^^^^^^^^^^^^^
- // You can plan a cartesian path directly by specifying a list of waypoints
+ // You can plan a Cartesian path directly by specifying a list of waypoints
// for the end-effector to go through. Note that we are starting
// from the new start state above. The initial pose (start state) does not
// need to be added to the waypoint list but adding it can help with visualizations
@@ -263,8 +263,8 @@ int main(int argc, char **argv)
// of the maxiumum speed of each joint. Note this is not the speed of the end effector point.
move_group.setMaxVelocityScalingFactor(0.1);
- // We want the cartesian path to be interpolated at a resolution of 1 cm
- // which is why we will specify 0.01 as the max step in cartesian
+ // We want the Cartesian path to be interpolated at a resolution of 1 cm
+ // which is why we will specify 0.01 as the max step in Cartesian
// translation. We will specify the jump threshold as 0.0, effectively disabling it.
// Warning - disabling the jump threshold while operating real hardware can cause
// large unpredictable motions of redundant joints and could be a safety issue
@@ -272,9 +272,9 @@ int main(int argc, char **argv)
const double jump_threshold = 0.0;
const double eef_step = 0.01;
double fraction = move_group.computeCartesianPath(waypoints, eef_step, jump_threshold, trajectory);
- ROS_INFO_NAMED("tutorial", "Visualizing plan 4 (cartesian path) (%.2f%% acheived)", fraction * 100.0);
+ ROS_INFO_NAMED("tutorial", "Visualizing plan 4 (Cartesian path) (%.2f%% acheived)", fraction * 100.0);
- // Visualize the plan in Rviz
+ // Visualize the plan in RViz
visual_tools.deleteAllMarkers();
visual_tools.publishText(text_pose, "Joint Space Goal", rvt::WHITE, rvt::XLARGE);
visual_tools.publishPath(waypoints, rvt::LIME_GREEN, rvt::SMALL);
@@ -319,7 +319,7 @@ int main(int argc, char **argv)
ROS_INFO_NAMED("tutorial", "Add an object into the world");
planning_scene_interface.addCollisionObjects(collision_objects);
- // Show text in Rviz of status
+ // Show text in RViz of status
visual_tools.publishText(text_pose, "Add object", rvt::WHITE, rvt::XLARGE);
visual_tools.trigger();
@@ -338,7 +338,7 @@ int main(int argc, char **argv)
success = (move_group.plan(my_plan) == moveit::planning_interface::MoveItErrorCode::SUCCESS);
ROS_INFO_NAMED("tutorial", "Visualizing plan 5 (pose goal move around cuboid) %s", success ? "" : "FAILED");
- // Visualize the plan in Rviz
+ // Visualize the plan in RViz
visual_tools.deleteAllMarkers();
visual_tools.publishText(text_pose, "Obstacle Goal", rvt::WHITE, rvt::XLARGE);
visual_tools.publishTrajectoryLine(my_plan.trajectory_, joint_model_group);
@@ -349,7 +349,7 @@ int main(int argc, char **argv)
ROS_INFO_NAMED("tutorial", "Attach the object to the robot");
move_group.attachObject(collision_object.id);
- // Show text in Rviz of status
+ // Show text in RViz of status
visual_tools.publishText(text_pose, "Object attached to robot", rvt::WHITE, rvt::XLARGE);
visual_tools.trigger();
@@ -360,7 +360,7 @@ int main(int argc, char **argv)
ROS_INFO_NAMED("tutorial", "Detach the object from the robot");
move_group.detachObject(collision_object.id);
- // Show text in Rviz of status
+ // Show text in RViz of status
visual_tools.publishText(text_pose, "Object dettached from robot", rvt::WHITE, rvt::XLARGE);
visual_tools.trigger();
@@ -373,11 +373,11 @@ int main(int argc, char **argv)
object_ids.push_back(collision_object.id);
planning_scene_interface.removeCollisionObjects(object_ids);
- // Show text in Rviz of status
+ // Show text in RViz of status
visual_tools.publishText(text_pose, "Object removed", rvt::WHITE, rvt::XLARGE);
visual_tools.trigger();
- /* Sleep to give Rviz time to show the object is no longer there.*/
+ /* Sleep to give RViz time to show the object is no longer there.*/
ros::Duration(1.0).sleep();
// END_TUTORIAL
diff --git a/doc/move_group_python_interface/move_group_python_interface_tutorial.rst b/doc/move_group_python_interface/move_group_python_interface_tutorial.rst
index 8ae5d6070a..e637cc34fe 100644
--- a/doc/move_group_python_interface/move_group_python_interface_tutorial.rst
+++ b/doc/move_group_python_interface/move_group_python_interface_tutorial.rst
@@ -13,14 +13,14 @@ If you haven't already done so, make sure you've completed the steps in `Getting
The entire code
---------------
-The entire code can be seen :codedir:`here in the MoveIt! Github project`.
+The entire code can be seen :codedir:`here in the MoveIt! GitHub project`.
.. tutorial-formatter:: ./scripts/move_group_python_interface_tutorial.py
The launch file
---------------
The entire launch file is :codedir:`here`
-on github. All the code in this tutorial can be run from the
+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.
Running the code
@@ -30,13 +30,13 @@ Make sure your python file is executable: ::
roscd moveit_tutorials/doc/move_group_python_interface/scripts/
chmod +x move_group_python_interface_tutorial.py
-Start Rviz and MoveGroup node
+Start RViz and MoveGroup node
-----------------------------
Open two shells and make sure you have re-sourced the setup files in both shells: ::
source ~/ws_moveit/devel/setup.bash
-Start Rviz and wait for everything to finish loading in the first shell: ::
+Start RViz and wait for everything to finish loading in the first shell: ::
roslaunch panda_moveit_config demo.launch
@@ -47,11 +47,11 @@ Now run the python code directly in the other shell using rosrun: ::
Expected Output
---------------
-Watch the `YouTube video demo `_ for expected output. In Rviz, we should be able to see the following:
+Watch the `YouTube video demo `_ for expected output. In RViz, we should be able to see the following:
Press ** in the shell where you ran the ``rosrun`` command between each step
1. The robot plans and moves its arm to the joint goal.
2. The robot plans a path to a pose goal.
3. The robot displays the plan to the same goal again.
4. The robot moves its arm to the joint goal to the side.
- 5. The robot moves its arm along the desired cartesian path.
+ 5. The robot moves its arm along the desired Cartesian path.
diff --git a/doc/move_group_python_interface/scripts/move_group_python_interface_tutorial.py b/doc/move_group_python_interface/scripts/move_group_python_interface_tutorial.py
index 38c7c664c0..d3aa305141 100755
--- a/doc/move_group_python_interface/scripts/move_group_python_interface_tutorial.py
+++ b/doc/move_group_python_interface/scripts/move_group_python_interface_tutorial.py
@@ -78,7 +78,7 @@
## We create this DisplayTrajectory publisher which is used below to publish
- ## trajectories for Rviz to visualize.
+ ## trajectories for RViz to visualize.
display_trajectory_publisher = rospy.Publisher(
'/move_group/display_planned_path',
moveit_msgs.msg.DisplayTrajectory,
@@ -124,7 +124,7 @@
## group
group.go(joints, wait=True)
- print "============ Press Enter to Continue the Tutorial After Rviz Displays Plan1..."
+ print "============ Press Enter to Continue the Tutorial After RViz Displays Plan1..."
raw_input()
group.stop()
@@ -144,10 +144,10 @@
## to actually move the robot
plan1 = group.plan()
- print "============ Press Enter to Continue the Tutorial After Rviz Displays Plan2..."
+ print "============ Press Enter to Continue the Tutorial After RViz Displays Plan2..."
raw_input()
- ## You can ask Rviz to visualize a plan (aka trajectory) for you. But the
+ ## You can ask RViz to visualize a plan (aka trajectory) for you. But the
## group.plan() method does this automatically so this is not that useful
## here (it just displays the same trajectory again).
print "============ Visualizing plan1"
@@ -157,7 +157,7 @@
display_trajectory.trajectory.append(plan1)
display_trajectory_publisher.publish(display_trajectory);
- print "============ Press Enter to Continue the Tutorial After Rviz Displays Plan2 (again)..."
+ print "============ Press Enter to Continue the Tutorial After RViz Displays Plan2 (again)..."
raw_input()
## Moving to a pose goal
@@ -197,13 +197,13 @@
plan2 = group.plan()
- print "============ Press Enter to Continue the Tutorial After Rviz Displays Plan3..."
+ print "============ Press Enter to Continue the Tutorial After RViz Displays Plan3..."
raw_input()
## Cartesian Paths
## ^^^^^^^^^^^^^^^
- ## You can plan a cartesian path directly by specifying a list of waypoints
+ ## You can plan a Cartesian path directly by specifying a list of waypoints
## for the end-effector to go through.
waypoints = []
@@ -221,15 +221,15 @@
wpose.position.y += 0.3
waypoints.append(copy.deepcopy(wpose))
- ## We want the cartesian path to be interpolated at a resolution of 1 cm
- ## which is why we will specify 0.01 as the eef_step in cartesian
+ ## We want the Cartesian path to be interpolated at a resolution of 1 cm
+ ## which is why we will specify 0.01 as the eef_step in Cartesian
## translation. We will specify the jump threshold to 0.0 disabling it.
(plan3, fraction) = group.compute_cartesian_path(
waypoints, # waypoints to follow
0.01, # eef_step
0.0) # jump_threshold
- print "============ Press Enter to Continue the Tutorial After Rviz Displays Plan4..."
+ print "============ Press Enter to Continue the Tutorial After RViz Displays Plan4..."
raw_input()
# Uncomment the line below to execute this plan on a real robot.
diff --git a/doc/moveit_commander/moveit_commander_tutorial.rst b/doc/moveit_commander/moveit_commander_tutorial.rst
index 96889ff7d9..f97b7663cf 100644
--- a/doc/moveit_commander/moveit_commander_tutorial.rst
+++ b/doc/moveit_commander/moveit_commander_tutorial.rst
@@ -7,13 +7,13 @@ Getting Started
---------------
If you haven't already done so, make sure you've completed the steps in `Getting Started <../getting_started/getting_started.html>`_.
-Starting Rviz and the Command Line Tool
+Starting RViz and the Command Line Tool
---------------------------------------
Open two shells and make sure you have sourced the setup files in both shells: ::
source ~/ws_moveit/devel/setup.bash
-Start Rviz and wait for everything to finish loading in the first shell: ::
+Start RViz and wait for everything to finish loading in the first shell: ::
roslaunch panda_moveit_config demo.launch
@@ -52,6 +52,6 @@ Instead of calling ``go`` you could also type: ::
plan goal
execute
-This is slightly inefficient, but the advantage is that the ``plan`` command allows you to visualize the computed motion plan in Rviz before you actually issue the execute command.
+This is slightly inefficient, but the advantage is that the ``plan`` command allows you to visualize the computed motion plan in RViz before you actually issue the execute command.
For a list of supported commands, you can type ``help``. To exit the ``moveit_commander`` interface you can type ``quit``.
diff --git a/doc/perception_configuration/perception_configuration_tutorial.rst b/doc/perception_configuration/perception_configuration_tutorial.rst
index 7b802b5a3a..2c21c622ff 100644
--- a/doc/perception_configuration/perception_configuration_tutorial.rst
+++ b/doc/perception_configuration/perception_configuration_tutorial.rst
@@ -3,7 +3,7 @@ Perception/Configuration
In this section, we will walk through configuring the 3D sensors on your robot with MoveIt!. The primary component in MoveIt! that deals with 3D perception is the Occupancy Map Updater. The updater uses a plugin architecture to process different types of input. The currently available plugins in MoveIt! are:
-* The PointCloud Occupany Map Updater: which can take as input point clouds (``sensor_msgs/PointCloud2``)
+* The PointCloud Occupancy Map Updater: which can take as input point clouds (``sensor_msgs/PointCloud2``)
* The Depth Image Occupancy Map Updater: which can take as input Depth Images (``sensor_msgs/Image``)
@@ -43,7 +43,7 @@ We will have to generate a YAML configuration file for configuring the 3D sensor
YAML Configuration file (Depth Map)
-----------------------------------
-We will have to generate a YAML configuration file for configuring the 3D sensors. An `example file for processing depth images `_ can be found in the `panda_moveit_config repo `_ as well: ::
+We will have to generate a YAML configuration file for configuring the 3D sensors. An `example file for processing depth images `_ can be found in the `panda_moveit_config repository `_ as well: ::
sensors:
- sensor_plugin: occupancy_map_monitor/DepthImageOctomapUpdater
diff --git a/doc/planning_scene/launch/planning_scene_tutorial.launch b/doc/planning_scene/launch/planning_scene_tutorial.launch
index 1df7e9c254..e1cb3c45d6 100644
--- a/doc/planning_scene/launch/planning_scene_tutorial.launch
+++ b/doc/planning_scene/launch/planning_scene_tutorial.launch
@@ -1,5 +1,5 @@
-
+
diff --git a/doc/planning_scene/planning_scene_tutorial.rst b/doc/planning_scene/planning_scene_tutorial.rst
index 0c24385da1..5a5dd44d02 100644
--- a/doc/planning_scene/planning_scene_tutorial.rst
+++ b/doc/planning_scene/planning_scene_tutorial.rst
@@ -11,13 +11,13 @@ If you haven't already done so, make sure you've completed the steps in `Getting
The entire code
---------------
-The entire code can be seen :codedir:`here in the MoveIt! Github project`.
+The entire code can be seen :codedir:`here in the MoveIt! GitHub project`.
.. tutorial-formatter:: ./src/planning_scene_tutorial.cpp
The launch file
---------------
-The entire launch file is :codedir:`here ` on github. All the code in this tutorial can be compiled and run from the moveit_tutorials package.
+The entire launch file is :codedir:`here ` on GitHub. All the code in this tutorial can be compiled and run from the moveit_tutorials package.
Running the code
----------------
diff --git a/doc/planning_scene_ros_api/planning_scene_ros_api_tutorial.rst b/doc/planning_scene_ros_api/planning_scene_ros_api_tutorial.rst
index 86520753a4..0112e22ff8 100644
--- a/doc/planning_scene_ros_api/planning_scene_ros_api_tutorial.rst
+++ b/doc/planning_scene_ros_api/planning_scene_ros_api_tutorial.rst
@@ -17,7 +17,7 @@ Open two shells and make sure you have re-sourced the setup files in both of the
source ~/ws_moveit/devel/setup.bash
-In the first shell start Rviz and wait for everything to finish loading: ::
+In the first shell start RViz and wait for everything to finish loading: ::
roslaunch panda_moveit_config demo.launch
@@ -27,7 +27,7 @@ In the second shell, run the launch file for this demo: ::
Expected Output
---------------
-In rviz, you should be able to see the following:
+In RViz, you should be able to see the following:
* Object appear in the planning scene
* Object gets attached to the robot
* Object gets detached from the robot
diff --git a/doc/planning_scene_ros_api/src/planning_scene_ros_api_tutorial.cpp b/doc/planning_scene_ros_api/src/planning_scene_ros_api_tutorial.cpp
index ccf68f5a79..b88637205f 100644
--- a/doc/planning_scene_ros_api/src/planning_scene_ros_api_tutorial.cpp
+++ b/doc/planning_scene_ros_api/src/planning_scene_ros_api_tutorial.cpp
@@ -62,7 +62,7 @@ int main(int argc, char **argv)
// Visualization
// ^^^^^^^^^^^^^
// The package MoveItVisualTools provides many capabilties for visualizing objects, robots,
- // and trajectories in Rviz as well as debugging tools such as step-by-step introspection of a script
+ // and trajectories in RViz as well as debugging tools such as step-by-step introspection of a script
moveit_visual_tools::MoveItVisualTools visual_tools("panda_link0");
visual_tools.deleteAllMarkers();
diff --git a/doc/planning_with_approximated_constraint_manifolds/planning_with_approximated_constraint_manifolds_tutorial.rst b/doc/planning_with_approximated_constraint_manifolds/planning_with_approximated_constraint_manifolds_tutorial.rst
index 357fac01e6..9413fb3946 100644
--- a/doc/planning_with_approximated_constraint_manifolds/planning_with_approximated_constraint_manifolds_tutorial.rst
+++ b/doc/planning_with_approximated_constraint_manifolds/planning_with_approximated_constraint_manifolds_tutorial.rst
@@ -1,8 +1,8 @@
Planning with Approximated Constraint Manifolds
===============================================
-OMPL supports custom constraints to enable planning trajectories that follow a desired behaviour.
-Constraints can be defined in joint space and cartesian space where the latter is either orientation or position based.
+OMPL supports custom constraints to enable planning trajectories that follow a desired behavior.
+Constraints can be defined in joint space and Cartesian space where the latter is either orientation or position based.
While planning a trajectory each joint state needs to follow all of the set constraints, which is performed by rejection sampling by default.
This however might lead to very long planning times, especially when the constraints are very restrictive and the rejection rate is correspondingly high.
@@ -57,8 +57,8 @@ Graph size
Obviously stable planning results require a detailed approximation, thus the higher the **samples** is the more reliable the performance.
However higher values lead to linearly longer construction time for the database.
-Finding an appropriate size of the manifold is a problem that is highly dependend on how restrictive the constraints are.
-For most constraints it should suffice to use values in range of 1000 to 10000 with no noticable improvements with higher values as suggested in the paper.
+Finding an appropriate size of the manifold is a problem that is highly dependent on how restrictive the constraints are.
+For most constraints it should suffice to use values in range of 1000 to 10000 with no noticeable improvements with higher values as suggested in the paper.
Edges
"""""
@@ -67,7 +67,7 @@ Adding edges to the manifold is **optional** and can be disabled by setting **ed
Trajectory planning will work without edges in most cases just fine since the sampling process only needs the states to function.
**max_edge_length** defines the maximum distance of two states that allows an edge between them to be added.
By setting **explicit_motions** to *true* the edges are also enforced to match the constraints, making them represent valid paths between adjacent states.
-That is advantagous especially in approximations that are very sparse with many regions that are hard to reach since absolute distance is not necessary a measure for reachability.
+That is advantageous especially in approximations that are very sparse with many regions that are hard to reach since absolute distance is not necessary a measure for reachability.
The check if an edge matches a constraint is done by testing linearly interpolated points between the state pair.
The number of these interpolated points is set to **explicit_points_resolution** times the edge length and is limited by **max_explicit_points**.
@@ -82,7 +82,7 @@ After adding the constraints to the ConstraintsLibrary object the database can b
Database Loading and Usage
--------------------------
-The constraints database must be loaded at launch of the movegroup by setting the ros param::
+The constraints database must be loaded at launch of the move group node by setting the ros parameter::
diff --git a/doc/setup_assistant/setup_assistant_tutorial.rst b/doc/setup_assistant/setup_assistant_tutorial.rst
index 2b8ab7e68a..efb83486f7 100644
--- a/doc/setup_assistant/setup_assistant_tutorial.rst
+++ b/doc/setup_assistant/setup_assistant_tutorial.rst
@@ -20,7 +20,7 @@ MoveIt! and ROS
* Follow the instructions for :moveit_website:`installing MoveIt!`
first if you have not already done that.
-* If you haven't already done so, make sure you have the `franka description
+* If you haven't already done so, make sure you have the `Franka description
package `_ for Kinetic: ::
sudo apt-get install ros-kinetic-franka-description
@@ -248,7 +248,7 @@ files that you will need to start using MoveIt!
* Click on the *Configuration Files* pane. Choose a location and
name for the ROS package that will be generated containing your new
set of configuration files. Click browse, select a good
- location (for example, your home dir), click **Create New Folder**, call it
+ location (for example, your home directory), click **Create New Folder**, call it
"panda_moveit_config", and click **Choose**.
"panda_moveit_config" is the location used in the rest of the
documentation on this wiki. This package does not have to be within your
@@ -271,11 +271,11 @@ What's Next
---------------
-The MoveIt! Rviz plugin
+The MoveIt! RViz plugin
* Start looking at how you can use the generated configuration files
to play with MoveIt! using the
- `MoveIt! Rviz Plugin <../visualization/visualization_tutorial.html>`_.
+ `MoveIt! RViz Plugin <../visualization/visualization_tutorial.html>`_.
Setup IKFast Inverse Kinematics Solver
diff --git a/doc/time_parameterization/time_parameterization_tutorial.rst b/doc/time_parameterization/time_parameterization_tutorial.rst
index 357c0afb6e..0aff84c26d 100644
--- a/doc/time_parameterization/time_parameterization_tutorial.rst
+++ b/doc/time_parameterization/time_parameterization_tutorial.rst
@@ -12,12 +12,12 @@ By default MoveIt! sets the velocity and acceleration of a joint trajectory to t
During Runtime
^^^^^^^^^^^^^^
-The speed of a parameterized kinematic trajectory can also be modified during runtime as a fraction of the max velocity and acceleration set in the configuration values, as a value between 0-1. To change the speed on a per-motion plan basis, you can set the two scaling factors as described in `MotionPlanRequest.msg `_. Spinboxes for setting both of those factors are also available in the `MoveIt! MotionPlanning rviz plugin <../visualization/visualization_tutorial.html>`_.
+The speed of a parameterized kinematic trajectory can also be modified during runtime as a fraction of the max velocity and acceleration set in the configuration values, as a value between 0-1. To change the speed on a per-motion plan basis, you can set the two scaling factors as described in `MotionPlanRequest.msg `_. Spinboxes for setting both of those factors are also available in the `MoveIt! MotionPlanning RViz plugin <../visualization/visualization_tutorial.html>`_.
Time Parameterization Algorithms
--------------------------------
MoveIt! can support different algorithms for post-processing a kinematic trajectory to add timestamps and velocity/acceleration values. Currently two are available by default in MoveIt!: `Iterative Parabolic Time Parameterization `_, and `Iterative Spline Parameterization `_.
-The Iterative Parabolic Time Parameterization algorithm is used by default in the `Motion Planning Pipeline <../motion_planning_pipeline/motion_planning_pipeline_tutorial.html>`_ as a Planning Request Adaptor as documented in `this tutorial <../motion_planning_pipeline/motion_planning_pipeline_tutorial.html#using-a-planning-request-adapter>`_. Although the Iterative Parabolic Time Parameterization algorithm MoveIt! uses has been used by hundreds of robots over the years, there is known `bug with it `_.
+The Iterative Parabolic Time Parameterization algorithm is used by default in the `Motion Planning Pipeline <../motion_planning_pipeline/motion_planning_pipeline_tutorial.html>`_ as a Planning Request Adapter as documented in `this tutorial <../motion_planning_pipeline/motion_planning_pipeline_tutorial.html#using-a-planning-request-adapter>`_. Although the Iterative Parabolic Time Parameterization algorithm MoveIt! uses has been used by hundreds of robots over the years, there is known `bug with it `_.
-The Iterative Spline Parameterization algoritm was recently merged into mainstream MoveIt! in `PR 382 `_ to deal with these issues. While preliminary experiments are very promising, we are waiting for more feedback from the community before replacing the Iterative Parabolic Time Parameterization algorithm completely.
\ No newline at end of file
+The Iterative Spline Parameterization algorithm was recently merged into mainstream MoveIt! in `PR 382 `_ to deal with these issues. While preliminary experiments are very promising, we are waiting for more feedback from the community before replacing the Iterative Parabolic Time Parameterization algorithm completely.
\ No newline at end of file
diff --git a/doc/trac_ik/trac_ik_tutorial.rst b/doc/trac_ik/trac_ik_tutorial.rst
index ba72f31704..8c8c6e2293 100644
--- a/doc/trac_ik/trac_ik_tutorial.rst
+++ b/doc/trac_ik/trac_ik_tutorial.rst
@@ -1,9 +1,9 @@
-Trac-IK Kinematics Solver
+TRAC-IK Kinematics Solver
=========================
-`Trac-IK `_ is an inverse kinematics solver developed by Traclabs that combines two IK implementations via threading to achieve more reliable solutions than common available open source IK solvers. From their documentation:
+`TRAC-IK `_ is an inverse kinematics solver developed by TRACLabs that combines two IK implementations via threading to achieve more reliable solutions than common available open source IK solvers. From their documentation:
- (Trac-IK) provides an alternative Inverse Kinematics solver to the popular inverse Jacobian methods in KDL. Specifically, KDL's convergence algorithms are based on Newton's method, which does not work well in the presence of joint limits --- common for many robotic platforms. TRAC-IK concurrently runs two IK implementations. One is a simple extension to KDL's Newton-based convergence algorithm that detects and mitigates local minima due to joint limits by random jumps. The second is an SQP (Sequential Quadratic Programming) nonlinear optimization approach which uses quasi-Newton methods that better handle joint limits. By default, the IK search returns immediately when either of these algorithms converges to an answer. Secondary constraints of distance and manipulability are also provided in order to receive back the "best" IK solution.
+ (TRAC-IK) provides an alternative Inverse Kinematics solver to the popular inverse Jacobian methods in KDL. Specifically, KDL's convergence algorithms are based on Newton's method, which does not work well in the presence of joint limits --- common for many robotic platforms. TRAC-IK concurrently runs two IK implementations. One is a simple extension to KDL's Newton-based convergence algorithm that detects and mitigates local minima due to joint limits by random jumps. The second is an SQP (Sequential Quadratic Programming) nonlinear optimization approach which uses quasi-Newton methods that better handle joint limits. By default, the IK search returns immediately when either of these algorithms converges to an answer. Secondary constraints of distance and manipulability are also provided in order to receive back the "best" IK solution.
The package `trac_ik_kinematics_plugin `_ provides a KinematicsBase MoveIt! interface that can replace the default KDL solver. Currently mimic joints are *not* supported.
diff --git a/doc/urdf_srdf/urdf_srdf_tutorial.rst b/doc/urdf_srdf/urdf_srdf_tutorial.rst
index 2029d50006..e6fad29606 100644
--- a/doc/urdf_srdf/urdf_srdf_tutorial.rst
+++ b/doc/urdf_srdf/urdf_srdf_tutorial.rst
@@ -10,7 +10,7 @@ URDF Resources
* `URDF ROS Wiki Page `_ - The URDF ROS Wiki page is the source of most information about the URDF.
* `URDF Tutorials `_ - Tutorials for working with the URDF.
-* `Solidworks URDF Plugin `_ - A plugin that lets you generate a URDF directly from a Solidworks model.
+* `SOLIDWORKS URDF Plugin `_ - A plugin that lets you generate a URDF directly from a SOLIDWORKS model.
Important Tips
^^^^^^^^^^^^^^
@@ -76,7 +76,7 @@ Serial Chain
""""""""""""
A serial chain is specified using the base link and the tip link. The tip link in a chain is the child link of the last joint in the chain. The base link in a chain is the parent link for the first joint in the chain.
-Collection of Sub-groups
+Collection of Sub-Groups
""""""""""""""""""""""""
A group can also be a collection of groups. E.g., you can define the panda_arm and panda_arm as two groups and then define a new group called both_arms that includes these two groups.
diff --git a/doc/visualization/visualization_tutorial.rst b/doc/visualization/visualization_tutorial.rst
index 9737079d93..1af2a4d428 100644
--- a/doc/visualization/visualization_tutorial.rst
+++ b/doc/visualization/visualization_tutorial.rst
@@ -1,4 +1,4 @@
-Visualization with MoveIt! RViz Plugin
+Visualization with the MoveIt! RViz Plugin
===============================================
MoveIt! comes with a plugin for the ROS Visualizer (RViz). The plugin allows you to setup scenes in which the robot will work, generate plans, visualize the output and interact directly with a visualized robot. We will explore the plugin in this tutorial.
@@ -7,7 +7,7 @@ Getting Started
---------------
If you haven't already done so, make sure you've completed the steps in `Getting Started <../getting_started/getting_started.html>`_.
-Step 1: Launch the demo and Configure the Plugin
+Step 1: Launch the Demo and Configure the Plugin
------------------------------------------------
* Launch the demo: ::
@@ -16,7 +16,7 @@ Step 1: Launch the demo and Configure the Plugin
* If you are doing this for the first time, you may have to add the Motion Planning Plugin.
- * In the Rviz Displays Tab, press *Add*
+ * In the RViz Displays Tab, press *Add*
* From the moveit_ros_visualization folder, choose "MotionPlanning" as the DisplayType. Press "Ok".
@@ -41,7 +41,7 @@ Step 1: Launch the demo and Configure the Plugin
.. image:: rviz_plugin_start.png
:width: 700px
-Step 2: Play with the visualized robots
+Step 2: Play with the Visualized Robots
---------------------------------------
There are four different overlapping visualizations:
@@ -71,7 +71,7 @@ The display states for each of these visualizations can be toggled on and off us
Step 3: Interact with the Panda
-------------------------------
-* Press **Interact** in the top menu of rviz (Note: some tools may be hidden, press **+** in the top menu to add the **Interact** tool as shown below). You should see a couple of interactive markers appear for the arm of the Panda.
+* Press **Interact** in the top menu of RViz (Note: some tools may be hidden, press **+** in the top menu to add the **Interact** tool as shown below). You should see a couple of interactive markers appear for the arm of the Panda.
* One marker (corresponding to the orange colored right arm) will be used to set the "Goal State" for motion planning. Another marker corresponding to a green colored representation of the right arm will be used to set the "Start State" for motion planning.
@@ -80,7 +80,7 @@ Step 3: Interact with the Panda
.. image:: rviz_plugin_interact.png
:width: 700px
-Moving into collision
+Moving into Collision
+++++++++++++++++++++
Note what happens when you try to move one of the arms into collision with the other. The two links that are in collision will turn red.
@@ -88,12 +88,12 @@ Note what happens when you try to move one of the arms into collision with the o
.. image:: rviz_plugin_collision.png
:width: 700px
-The "Use Collision-Aware IK" checkbox found within the MotionPlanning plugin allows you to toggle the behavior of the IK solver. When the checkbox is ticked, the solver will keep attempting to find a collision-free solution for the desired end-effector pose. When it is unticked, the solver will allow collisions to happen in the solution. The links in collision will always still be visualized in red, regardless of the state of the checkbox.
+The "Use Collision-Aware IK" checkbox found within the MotionPlanning plugin allows you to toggle the behavior of the IK solver. When the checkbox is ticked, the solver will keep attempting to find a collision-free solution for the desired end-effector pose. When it is not checked, the solver will allow collisions to happen in the solution. The links in collision will always still be visualized in red, regardless of the state of the checkbox.
.. image:: rviz_plugin_collision_aware_ik_checkbox.png
:width: 700px
-Moving out of reachable workspace
+Moving out of Reachable Workspace
+++++++++++++++++++++++++++++++++
Note also what happens when you try to move an end-effector out of its reachable workspace.
@@ -104,7 +104,7 @@ Note also what happens when you try to move an end-effector out of its reachable
Step 4: Use Motion Planning with the Panda
-------------------------------------------
-* Now, you can start motion planning with the Panda in the MoveIt! Rviz Plugin.
+* Now, you can start motion planning with the Panda in the MoveIt! RViz Plugin.
* Move the Start State to a desired location.
@@ -121,7 +121,7 @@ Step 4: Use Motion Planning with the Panda
.. image:: rviz_plugin_planned_path.png
:width: 700px
-Introspecting trajectory waypoints
+Introspecting Trajectory Waypoints
++++++++++++++++++++++++++++++++++
*Available since: Indigo 0.7.10, Kinetic and Lunar 0.9.7*
diff --git a/index.rst b/index.rst
index 7fe0fac7f0..0b85fab103 100644
--- a/index.rst
+++ b/index.rst
@@ -5,7 +5,7 @@ These tutorials will run you through how to use MoveIt! with your robot. It is a
.. note:: All tutorials referencing the Panda have only been tested with ROS Kinetic. For earlier versions of ROS (eg. indigo) See `the ROS Indigo tutorials with the PR2 here `_
-To follow along with these tutorials you will need a **ROBOT_moveit_config** package. This tutorial will use the Panda robot from Franka Emika. To get a working **panda_movit_config** package you can install from source, create your own, or install from Debian. We will walk through each method in the following tutuorial:
+To follow along with these tutorials you will need a **ROBOT_moveit_config** package. This tutorial will use the Panda robot from Franka Emika. To get a working **panda_movit_config** package you can install from source, create your own, or install from Debian. We will walk through each method in the following tutorial:
Getting Started with MoveIt! and RViz
@@ -82,7 +82,7 @@ Attribution
-----------
Major contributors to the MoveIt! tutorials are listed in chronological order: Sachin Chitta, Dave Hershberger, Acorn Pooley, Dave Coleman, Michael Gorner, Francisco Suarez, Mike Lautman. Help us improve these docs and we'll be happy to include you here also!
-The tutorials had a major update in 2018 during a codesprint sponsored by Franka Emika in collaboration with PickNik (`Check out the blog post! `_)
+The tutorials had a major update in 2018 during a code sprint sponsored by Franka Emika in collaboration with PickNik (`Check out the blog post! `_)
.. image:: ./_static/franka_logo.png
:width: 300px