diff --git a/doc/examples/collision_environments/src/collision_scene_example.cpp b/doc/examples/collision_environments/src/collision_scene_example.cpp index 9081506c8e..a55b0385d8 100644 --- a/doc/examples/collision_environments/src/collision_scene_example.cpp +++ b/doc/examples/collision_environments/src/collision_scene_example.cpp @@ -1,12 +1,12 @@ #include // MoveIt -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include // TF2 #include diff --git a/doc/examples/hybrid_planning/hybrid_planning_tutorial.rst b/doc/examples/hybrid_planning/hybrid_planning_tutorial.rst index a8475355d4..e8d6a47398 100644 --- a/doc/examples/hybrid_planning/hybrid_planning_tutorial.rst +++ b/doc/examples/hybrid_planning/hybrid_planning_tutorial.rst @@ -100,7 +100,7 @@ The dataflow within the component can be seen in the picture below: .. image:: images/global_planner_dataflow.png :width: 500pt -The *Global Planner Plugin* can be used to implement and customize the global planning algorithm. To implement you own planner you simply need to inherit from the :moveit_codedir:`GlobalPlannerInterface `: +The *Global Planner Plugin* can be used to implement and customize the global planning algorithm. To implement you own planner you simply need to inherit from the :moveit_codedir:`GlobalPlannerInterface `: .. code-block:: c++ @@ -140,7 +140,7 @@ Via the *Global Solution Subscriber* the *Local Planner Component* receives glob The behavior of the *Local Planner Component* can be customized via the *Trajectory Operator Plugin* and the local *Solver Plugin*: -The *Trajectory Operator Plugin* handles the reference trajectory. To create your own operator you need to create a plugin class which inherits from the :moveit_codedir:`TrajectoryOperatorInterface `: +The *Trajectory Operator Plugin* handles the reference trajectory. To create your own operator you need to create a plugin class which inherits from the :moveit_codedir:`TrajectoryOperatorInterface `: .. code-block:: c++ @@ -174,7 +174,7 @@ The *Trajectory Operator Plugin* handles the reference trajectory. To create you *Trajectory Operator* example implementations can be found :moveit_codedir:`here `. -The *Local Solver Plugin* implements the algorithm to solve the local planning problem each iteration. To implement your solution you need to inherit from the :moveit_codedir:`LocalConstraintSolverInterface `: +The *Local Solver Plugin* implements the algorithm to solve the local planning problem each iteration. To implement your solution you need to inherit from the :moveit_codedir:`LocalConstraintSolverInterface `: .. code-block:: c++ @@ -238,7 +238,7 @@ The callback function an event channel in the *Hybrid Planning Manager* looks li } }; -To create you own *Planner Logic Plugin* you need inherit from the :moveit_codedir:`PlannerLogicInterface `: +To create you own *Planner Logic Plugin* you need inherit from the :moveit_codedir:`PlannerLogicInterface `: .. code-block:: c++ @@ -259,4 +259,4 @@ To create you own *Planner Logic Plugin* you need inherit from the :moveit_coded ReactionResult react(const std::string& event) override; }; -A possible implementation of the *react()* function could contain a switch-case statement that maps events to actions like in the :moveit_codedir:`example logic plugins`. +A possible implementation of the *react()* function could contain a switch-case statement that maps events to actions like in the :moveit_codedir:`example logic plugins`. diff --git a/doc/examples/motion_planning_api/src/motion_planning_api_tutorial.cpp b/doc/examples/motion_planning_api/src/motion_planning_api_tutorial.cpp index 0bfb7c646f..b6737fea96 100644 --- a/doc/examples/motion_planning_api/src/motion_planning_api_tutorial.cpp +++ b/doc/examples/motion_planning_api/src/motion_planning_api_tutorial.cpp @@ -37,14 +37,14 @@ #include // MoveIt -#include -#include -#include -#include +#include +#include +#include +#include #include -#include +#include #include -#include +#include static const rclcpp::Logger LOGGER = rclcpp::get_logger("motion_planning_api_tutorial"); @@ -68,10 +68,10 @@ int main(int argc, char** argv) // interface to load any planner that you want to use. Before we can // load the planner, we need two objects, a RobotModel and a // PlanningScene. We will start by instantiating a - // :moveit_codedir:`RobotModelLoader` + // :moveit_codedir:`RobotModelLoader` // object, which will look up the robot description on the ROS // parameter server and construct a - // :moveit_codedir:`RobotModel` + // :moveit_codedir:`RobotModel` // for us to use. const std::string PLANNING_GROUP = "panda_arm"; robot_model_loader::RobotModelLoader robot_model_loader(motion_planning_api_tutorial_node, "robot_description"); @@ -81,9 +81,9 @@ int main(int argc, char** argv) const moveit::core::JointModelGroup* joint_model_group = robot_state->getJointModelGroup(PLANNING_GROUP); // Using the - // :moveit_codedir:`RobotModel`, + // :moveit_codedir:`RobotModel`, // we can construct a - // :moveit_codedir:`PlanningScene` + // :moveit_codedir:`PlanningScene` // that maintains the state of the world (including the robot). planning_scene::PlanningScenePtr planning_scene(new planning_scene::PlanningScene(robot_model)); @@ -186,7 +186,7 @@ int main(int argc, char** argv) // We will create the request as a constraint using a helper function available // from the - // :moveit_codedir:`kinematic_constraints` + // :moveit_codedir:`kinematic_constraints` // package. moveit_msgs::msg::Constraints pose_goal = kinematic_constraints::constructGoalConstraints("panda_link8", pose, tolerance_pose, tolerance_angle); diff --git a/doc/examples/motion_planning_pipeline/src/motion_planning_pipeline_tutorial.cpp b/doc/examples/motion_planning_pipeline/src/motion_planning_pipeline_tutorial.cpp index 61259cff64..9c66c63a5c 100644 --- a/doc/examples/motion_planning_pipeline/src/motion_planning_pipeline_tutorial.cpp +++ b/doc/examples/motion_planning_pipeline/src/motion_planning_pipeline_tutorial.cpp @@ -37,12 +37,12 @@ #include // MoveIt -#include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include +#include #include #include #include @@ -67,10 +67,10 @@ int main(int argc, char** argv) // a RobotModel and a PlanningScene. // // We will start by instantiating a - // :moveit_codedir:`RobotModelLoader` + // :moveit_codedir:`RobotModelLoader` // object, which will look up the robot description on the ROS // parameter server and construct a - // :moveit_codedir:`RobotModel` + // :moveit_codedir:`RobotModel` // for us to use. robot_model_loader::RobotModelLoaderPtr robot_model_loader( new robot_model_loader::RobotModelLoader(node, "robot_description")); @@ -158,7 +158,7 @@ int main(int argc, char** argv) // We will create the request as a constraint using a helper // function available from the - // :moveit_codedir:`kinematic_constraints` + // :moveit_codedir:`kinematic_constraints` // package. req.group_name = "panda_arm"; moveit_msgs::msg::Constraints pose_goal = diff --git a/doc/examples/move_group_interface/move_group_interface_tutorial.rst b/doc/examples/move_group_interface/move_group_interface_tutorial.rst index 8eb4a537d7..9d666dc3cc 100644 --- a/doc/examples/move_group_interface/move_group_interface_tutorial.rst +++ b/doc/examples/move_group_interface/move_group_interface_tutorial.rst @@ -5,7 +5,7 @@ Move Group C++ Interface .. image:: move_group_interface_tutorial_start_screen.png :width: 700px -In MoveIt, the simplest user interface is through the :moveit_codedir:`MoveGroupInterface` class. +In MoveIt, the simplest user interface is through the :moveit_codedir:`MoveGroupInterface` class. It provides easy to use functionality for most operations that a user may want to carry out, specifically setting joint or pose goals, creating motion plans, moving the robot, adding objects into the environment and attaching/detaching objects from the robot. This interface communicates over ROS topics, services, and actions to the :moveit_codedir:`MoveGroup` node. diff --git a/doc/examples/move_group_interface/src/move_group_interface_tutorial.cpp b/doc/examples/move_group_interface/src/move_group_interface_tutorial.cpp index 6a523a873a..787b0a8608 100644 --- a/doc/examples/move_group_interface/src/move_group_interface_tutorial.cpp +++ b/doc/examples/move_group_interface/src/move_group_interface_tutorial.cpp @@ -34,8 +34,8 @@ /* Author: Sachin Chitta, Dave Coleman, Mike Lautman */ -#include -#include +#include +#include #include #include @@ -74,12 +74,12 @@ int main(int argc, char** argv) static const std::string PLANNING_GROUP = "panda_arm"; // The - // :moveit_codedir:`MoveGroupInterface` + // :moveit_codedir:`MoveGroupInterface` // class can be easily set up using just the name of the planning group you would like to control and plan for. moveit::planning_interface::MoveGroupInterface move_group(move_group_node, PLANNING_GROUP); // We will use the - // :moveit_codedir:`PlanningSceneInterface` + // :moveit_codedir:`PlanningSceneInterface` // class to add and remove collision objects in our "virtual world" scene moveit::planning_interface::PlanningSceneInterface planning_scene_interface; diff --git a/doc/examples/moveit_cpp/src/moveit_cpp_tutorial.cpp b/doc/examples/moveit_cpp/src/moveit_cpp_tutorial.cpp index 355e01e410..1d2555fbed 100644 --- a/doc/examples/moveit_cpp/src/moveit_cpp_tutorial.cpp +++ b/doc/examples/moveit_cpp/src/moveit_cpp_tutorial.cpp @@ -1,8 +1,8 @@ #include #include // MoveitCpp -#include -#include +#include +#include #include diff --git a/doc/examples/planning_scene/planning_scene_tutorial.rst b/doc/examples/planning_scene/planning_scene_tutorial.rst index 63663d89cc..a037a06364 100644 --- a/doc/examples/planning_scene/planning_scene_tutorial.rst +++ b/doc/examples/planning_scene/planning_scene_tutorial.rst @@ -1,7 +1,7 @@ Planning Scene ================================== -The :moveit_codedir:`PlanningScene` class provides the main interface that you will use +The :moveit_codedir:`PlanningScene` class provides the main interface that you will use for collision checking and constraint checking. In this tutorial, we will explore the C++ interface to this class. diff --git a/doc/examples/planning_scene/src/planning_scene_tutorial.cpp b/doc/examples/planning_scene/src/planning_scene_tutorial.cpp index 76e20e11a5..60d44ad3b8 100644 --- a/doc/examples/planning_scene/src/planning_scene_tutorial.cpp +++ b/doc/examples/planning_scene/src/planning_scene_tutorial.cpp @@ -1,10 +1,10 @@ #include // MoveIt -#include -#include +#include +#include -#include +#include // BEGIN_SUB_TUTORIAL stateFeasibilityTestExample // @@ -38,12 +38,12 @@ int main(int argc, char** argv) // Setup // ^^^^^ // - // The :moveit_codedir:`PlanningScene` + // The :moveit_codedir:`PlanningScene` // class can be easily setup and configured using a - // :moveit_codedir:`RobotModel` + // :moveit_codedir:`RobotModel` // or a URDF and SRDF. This is, however, not the recommended way to instantiate a // PlanningScene. The - // :moveit_codedir:`PlanningSceneMonitor` + // :moveit_codedir:`PlanningSceneMonitor` // is the recommended method to create and maintain the current // planning scene (and is discussed in detail in the next tutorial) // using data from the robot's joints and the sensors on the robot. In @@ -64,9 +64,9 @@ int main(int argc, char** argv) // current state is in *self-collision*, i.e. whether the current // configuration of the robot would result in the robot's parts // hitting each other. To do this, we will construct a - // :moveit_codedir:`CollisionRequest` + // :moveit_codedir:`CollisionRequest` // object and a - // :moveit_codedir:`CollisionResult` + // :moveit_codedir:`CollisionResult` // object and pass them // into the collision checking function. Note that the result of // whether the robot is in self-collision or not is contained within @@ -151,7 +151,7 @@ int main(int argc, char** argv) // ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ // // The - // :moveit_codedir:`AllowedCollisionMatrix` + // :moveit_codedir:`AllowedCollisionMatrix` // (ACM) // provides a mechanism to tell the collision world to ignore // collisions between certain object: both parts of the robot and @@ -200,7 +200,7 @@ int main(int argc, char** argv) // The PlanningScene class also includes easy to use function calls // for checking constraints. The constraints can be of two types: // (a) constraints chosen from the - // :moveit_codedir:`KinematicConstraint` + // :moveit_codedir:`KinematicConstraint` // set: i.e. JointConstraint, PositionConstraint, OrientationConstraint and // VisibilityConstraint and (b) user // defined constraints specified through a callback. We will first @@ -213,7 +213,7 @@ int main(int argc, char** argv) // on the end-effector of the panda_arm group of the Panda robot. Note the // use of convenience functions for filling up the constraints // (these functions are found in the - // :moveit_codedir:`utils.h` + // :moveit_codedir:`utils.h` // file from the // kinematic_constraints directory in moveit_core). diff --git a/doc/examples/planning_scene_monitor/planning_scene_monitor_tutorial.rst b/doc/examples/planning_scene_monitor/planning_scene_monitor_tutorial.rst index a0a6f622e5..dc9e48f453 100644 --- a/doc/examples/planning_scene_monitor/planning_scene_monitor_tutorial.rst +++ b/doc/examples/planning_scene_monitor/planning_scene_monitor_tutorial.rst @@ -6,27 +6,27 @@ Planning Scene Monitor ================================== -The :moveit_codedir:`PlanningSceneMonitor` is the recommended interface for maintaining an up-to-date planning scene. The relationship between :moveit_codedir:`RobotState`, :moveit_codedir:`CurrentStateMonitor`, :moveit_codedir:`PlanningScene`, :moveit_codedir:`PlanningSceneMonitor`, and :moveit_codedir:`PlanningSceneInterface` can be really confusing at first. This tutorial aims to make clear these key concepts. +The :moveit_codedir:`PlanningSceneMonitor` is the recommended interface for maintaining an up-to-date planning scene. The relationship between :moveit_codedir:`RobotState`, :moveit_codedir:`CurrentStateMonitor`, :moveit_codedir:`PlanningScene`, :moveit_codedir:`PlanningSceneMonitor`, and :moveit_codedir:`PlanningSceneInterface` can be really confusing at first. This tutorial aims to make clear these key concepts. RobotState ---------- -The :moveit_codedir:`RobotState` is a snapshot of a robot. It contains the :moveit_codedir:`RobotModel` and a set of joint values. +The :moveit_codedir:`RobotState` is a snapshot of a robot. It contains the :moveit_codedir:`RobotModel` and a set of joint values. CurrentStateMonitor ------------------- -The :moveit_codedir:`CurrentStateMonitor` (CSM) can be thought of as a ROS wrapper for the RobotState. It subscribes to a provided topic for :common_interfaces_codedir:`JointState` messages that provide up-to-date sensor values for single degree of freedom actuators, such as revolute or prismatic joints, and updates its internal RobotState with those joint values. In addition to the single degree of freedom joints, a robot can have joints with multiple degrees of freedom such as floating and planar joints. To maintain up-to-date transform information for links and other frames attached with multiple-degree-of-freedom joints, the CSM stores a TF2 :ros_documentation:`Buffer ` that uses a TF2 :ros_documentation:`TransformListener ` to set their transforms in its internal data. +The :moveit_codedir:`CurrentStateMonitor` (CSM) can be thought of as a ROS wrapper for the RobotState. It subscribes to a provided topic for :common_interfaces_codedir:`JointState` messages that provide up-to-date sensor values for single degree of freedom actuators, such as revolute or prismatic joints, and updates its internal RobotState with those joint values. In addition to the single degree of freedom joints, a robot can have joints with multiple degrees of freedom such as floating and planar joints. To maintain up-to-date transform information for links and other frames attached with multiple-degree-of-freedom joints, the CSM stores a TF2 :ros_documentation:`Buffer ` that uses a TF2 :ros_documentation:`TransformListener ` to set their transforms in its internal data. PlanningScene ------------- -The :moveit_codedir:`PlanningScene` is a snapshot of the world that includes both the RobotState and any number of collision objects. The Planning Scene can be used for collision checking as well as getting information about the environment. +The :moveit_codedir:`PlanningScene` is a snapshot of the world that includes both the RobotState and any number of collision objects. The Planning Scene can be used for collision checking as well as getting information about the environment. PlanningSceneMonitor -------------------- -The :moveit_codedir:`PlanningSceneMonitor` wraps a PlanningScene with ROS interfaces for keeping the PlanningScene up to date. To access the PlanningSceneMonitor's underlying PlanningScene, use the provided :moveit_codedir:`LockedPlanningSceneRW` and :moveit_codedir:`LockedPlanningSceneRO` classes. +The :moveit_codedir:`PlanningSceneMonitor` wraps a PlanningScene with ROS interfaces for keeping the PlanningScene up to date. To access the PlanningSceneMonitor's underlying PlanningScene, use the provided :moveit_codedir:`LockedPlanningSceneRW` and :moveit_codedir:`LockedPlanningSceneRO` classes. The PlanningSceneMonitor has the following objects, which have their own ROS interfaces for keeping sub-components of the planning scene up to date: - * A :moveit_codedir:`CurrentStateMonitor` for tracking updates to the RobotState via a ``robot_state_subscriber_`` and a ``tf_buffer_``, as well as a planning scene subscriber for listening to planning scene diffs from other publishers. + * A :moveit_codedir:`CurrentStateMonitor` for tracking updates to the RobotState via a ``robot_state_subscriber_`` and a ``tf_buffer_``, as well as a planning scene subscriber for listening to planning scene diffs from other publishers. * An OccupancyMapMonitor for tracking updates to an OccupancyMap via ROS topics and services. The PlanningSceneMonitor has the following subscribers: @@ -49,4 +49,4 @@ The PlanningSceneMonitor is initialized with: PlanningSceneInterface ---------------------- -The :moveit_codedir:`PlanningSceneInterface` is a useful class for publishing updates to a MoveGroup's :moveit_codedir:`PlanningSceneMonitor` through a C++ API without creating your own subscribers and service clients. It may not work without MoveGroup or MoveItCpp. +The :moveit_codedir:`PlanningSceneInterface` is a useful class for publishing updates to a MoveGroup's :moveit_codedir:`PlanningSceneMonitor` through a C++ API without creating your own subscribers and service clients. It may not work without MoveGroup or MoveItCpp. diff --git a/doc/examples/planning_scene_ros_api/src/planning_scene_ros_api_tutorial.cpp b/doc/examples/planning_scene_ros_api/src/planning_scene_ros_api_tutorial.cpp index 16064d7629..4f09420368 100644 --- a/doc/examples/planning_scene_ros_api/src/planning_scene_ros_api_tutorial.cpp +++ b/doc/examples/planning_scene_ros_api/src/planning_scene_ros_api_tutorial.cpp @@ -44,9 +44,9 @@ #include #include -#include -#include -#include +#include +#include +#include #include diff --git a/doc/examples/robot_model_and_robot_state/robot_model_and_robot_state_tutorial.rst b/doc/examples/robot_model_and_robot_state/robot_model_and_robot_state_tutorial.rst index 0f67bd7686..6fc8990fb8 100644 --- a/doc/examples/robot_model_and_robot_state/robot_model_and_robot_state_tutorial.rst +++ b/doc/examples/robot_model_and_robot_state/robot_model_and_robot_state_tutorial.rst @@ -9,11 +9,11 @@ In this section, we will walk you through the C++ API for using kinematics in Mo The RobotModel and RobotState Classes ------------------------------------- -The :moveit_codedir:`RobotModel` and :moveit_codedir:`RobotState` classes are the core classes that give you access to a robot's kinematics. +The :moveit_codedir:`RobotModel` and :moveit_codedir:`RobotState` classes are the core classes that give you access to a robot's kinematics. -The :moveit_codedir:`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: :doc:`URDF and SRDF Tutorial ` +The :moveit_codedir:`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: :doc:`URDF and SRDF Tutorial ` -The :moveit_codedir:`RobotState` contains information about the robot at a certain point in time, storing vectors of joint positions and optionally velocities and accelerations. This information can be used to obtain kinematic information about the robot that depends on its current state, such as the Jacobian of an end effector. +The :moveit_codedir:`RobotState` contains information about the robot at a certain point in time, storing vectors of joint positions and optionally velocities and accelerations. This information can be used to obtain kinematic information about the robot that depends on its 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. diff --git a/doc/examples/robot_model_and_robot_state/src/robot_model_and_robot_state_tutorial.cpp b/doc/examples/robot_model_and_robot_state/src/robot_model_and_robot_state_tutorial.cpp index dd0130072d..d1f55f18f9 100644 --- a/doc/examples/robot_model_and_robot_state/src/robot_model_and_robot_state_tutorial.cpp +++ b/doc/examples/robot_model_and_robot_state/src/robot_model_and_robot_state_tutorial.cpp @@ -35,9 +35,9 @@ /* Author: Sachin Chitta, Michael Lautman*/ // MoveIt -#include -#include -#include +#include +#include +#include int main(int argc, char** argv) { @@ -66,18 +66,18 @@ int main(int argc, char** argv) // `RobotModelLoader`_ // object, which will look up // the robot description on the ROS parameter server and construct a - // :moveit_codedir:`RobotModel` for us to use. + // :moveit_codedir:`RobotModel` for us to use. // // .. _RobotModelLoader: - // https://github.com/moveit/moveit2/blob/main/moveit_ros/planning/robot_model_loader/include/moveit/robot_model_loader/robot_model_loader.h + // https://github.com/moveit/moveit2/blob/main/moveit_ros/planning/robot_model_loader/include/moveit/robot_model_loader/robot_model_loader.hpp robot_model_loader::RobotModelLoader robot_model_loader(node); const moveit::core::RobotModelPtr& kinematic_model = robot_model_loader.getModel(); RCLCPP_INFO(LOGGER, "Model frame: %s", kinematic_model->getModelFrame().c_str()); - // Using the :moveit_codedir:`RobotModel`, we can - // construct a :moveit_codedir:`RobotState` that + // Using the :moveit_codedir:`RobotModel`, we can + // construct a :moveit_codedir:`RobotState` that // maintains the configuration of the robot. We will set all joints in the state to their default values. We can then - // get a :moveit_codedir:`JointModelGroup`, + // get a :moveit_codedir:`JointModelGroup`, // which represents the robot model for a particular group, e.g. the "panda_arm" of the Panda robot. moveit::core::RobotStatePtr robot_state(new moveit::core::RobotState(kinematic_model)); robot_state->setToDefaultValues(); @@ -149,7 +149,8 @@ int main(int argc, char** argv) // Get the Jacobian // ^^^^^^^^^^^^^^^^ - // We can also get the Jacobian from the :moveit_codedir:`RobotState`. + // We can also get the Jacobian from the + // :moveit_codedir:`RobotState`. Eigen::Vector3d reference_point_position(0.0, 0.0, 0.0); Eigen::MatrixXd jacobian; robot_state->getJacobian(joint_model_group, robot_state->getLinkModel(joint_model_group->getLinkModelNames().back()), diff --git a/doc/examples/tests/test/tests.cpp b/doc/examples/tests/test/tests.cpp index de035fe4f1..be4c8e274d 100644 --- a/doc/examples/tests/test/tests.cpp +++ b/doc/examples/tests/test/tests.cpp @@ -36,8 +36,8 @@ // The Testing Framework and Utils #include -#include -#include +#include +#include // TF2 #include diff --git a/doc/examples/urdf_srdf/urdf_srdf_tutorial.rst b/doc/examples/urdf_srdf/urdf_srdf_tutorial.rst index 02d3f7c7a1..d2aa52d9c8 100644 --- a/doc/examples/urdf_srdf/urdf_srdf_tutorial.rst +++ b/doc/examples/urdf_srdf/urdf_srdf_tutorial.rst @@ -187,5 +187,5 @@ Then all of the other nodes may subscribe to the string message that gets publis Under the Hood: RDFLoader ^^^^^^^^^^^^^^^^^^^^^^^^^ -In many places in the MoveIt code, the robot description and semantics are loaded using the :moveit_codedir:`RDFLoader` +In many places in the MoveIt code, the robot description and semantics are loaded using the :moveit_codedir:`RDFLoader` class, which will attempt to read the parameters from the node, and if that fails, will attempt to subscribe to the String topic for a short period of time. If both methods fail to get the parameter, then a warning will be printed to the console. diff --git a/doc/how_to_guides/benchmarking/benchmarking_tutorial.rst b/doc/how_to_guides/benchmarking/benchmarking_tutorial.rst index 2eb57bcedc..f465777167 100644 --- a/doc/how_to_guides/benchmarking/benchmarking_tutorial.rst +++ b/doc/how_to_guides/benchmarking/benchmarking_tutorial.rst @@ -36,7 +36,7 @@ The database can be visualized by uploading the the file to `plannerarena.org ` file. +The benchmarks are configured by a set of ROS 2 parameters. You can learn more about these parameters in the :moveit_codedir:`BenchmarkOptions.hpp ` file. The BenchmarkExecutor Class diff --git a/doc/how_to_guides/benchmarking/config/benchmarks.yaml b/doc/how_to_guides/benchmarking/config/benchmarks.yaml index 63e6f14315..a1a6c5501a 100644 --- a/doc/how_to_guides/benchmarking/config/benchmarks.yaml +++ b/doc/how_to_guides/benchmarking/config/benchmarks.yaml @@ -1,4 +1,4 @@ -# A detailed description for all parameters can be found in BenchmarkOptions.h +# A detailed description for all parameters can be found in BenchmarkOptions.hpp parameters: name: FullBenchmark diff --git a/doc/how_to_guides/kinematics_cost_function/src/kinematics_cost_function_tutorial.cpp b/doc/how_to_guides/kinematics_cost_function/src/kinematics_cost_function_tutorial.cpp index b23ef352d1..247cf0ba04 100644 --- a/doc/how_to_guides/kinematics_cost_function/src/kinematics_cost_function_tutorial.cpp +++ b/doc/how_to_guides/kinematics_cost_function/src/kinematics_cost_function_tutorial.cpp @@ -33,10 +33,10 @@ *********************************************************************/ /* Author: Wyatt Rees */ -#include -#include -#include -#include +#include +#include +#include +#include #include #include @@ -75,7 +75,7 @@ int main(int argc, char** argv) static const std::string PLANNING_GROUP = "panda_arm"; // The - // :moveit_codedir:`MoveGroupInterface` + // :moveit_codedir:`MoveGroupInterface` // class can be easily set up using just the name of the planning group you would like to control and plan for. moveit::planning_interface::MoveGroupInterface move_group(node, PLANNING_GROUP); diff --git a/doc/how_to_guides/parallel_planning/src/parallel_planning_main.cpp b/doc/how_to_guides/parallel_planning/src/parallel_planning_main.cpp index 57d22aa6b0..96268cf363 100644 --- a/doc/how_to_guides/parallel_planning/src/parallel_planning_main.cpp +++ b/doc/how_to_guides/parallel_planning/src/parallel_planning_main.cpp @@ -1,19 +1,19 @@ #include #include // MoveitCpp -#include -#include +#include +#include #include #include // Warehouse -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include #include namespace rvt = rviz_visual_tools; diff --git a/doc/how_to_guides/pilz_industrial_motion_planner/pilz_industrial_motion_planner.rst b/doc/how_to_guides/pilz_industrial_motion_planner/pilz_industrial_motion_planner.rst index 99f70bd9d9..54f4ee6cc3 100644 --- a/doc/how_to_guides/pilz_industrial_motion_planner/pilz_industrial_motion_planner.rst +++ b/doc/how_to_guides/pilz_industrial_motion_planner/pilz_industrial_motion_planner.rst @@ -357,7 +357,7 @@ User interface sequence capability ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ A specialized MoveIt functionality known as the -:moveit_codedir:`command list manager` +:moveit_codedir:`command list manager` takes a ``moveit_msgs::msg::MotionSequenceRequest`` as input. The request contains a list of subsequent goals as described above and an additional ``blend_radius`` parameter. If the given ``blend_radius`` in meter is diff --git a/doc/how_to_guides/pilz_industrial_motion_planner/src/pilz_move_group.cpp b/doc/how_to_guides/pilz_industrial_motion_planner/src/pilz_move_group.cpp index 6356bfe3fa..6e58f9abcc 100644 --- a/doc/how_to_guides/pilz_industrial_motion_planner/src/pilz_move_group.cpp +++ b/doc/how_to_guides/pilz_industrial_motion_planner/src/pilz_move_group.cpp @@ -2,7 +2,7 @@ #include #include -#include +#include #include /** diff --git a/doc/how_to_guides/pilz_industrial_motion_planner/src/pilz_sequence.cpp b/doc/how_to_guides/pilz_industrial_motion_planner/src/pilz_sequence.cpp index 574b929fc5..45f210b80d 100644 --- a/doc/how_to_guides/pilz_industrial_motion_planner/src/pilz_sequence.cpp +++ b/doc/how_to_guides/pilz_industrial_motion_planner/src/pilz_sequence.cpp @@ -1,11 +1,11 @@ #include #include -#include -#include -#include -#include -#include +#include +#include +#include +#include +#include #include #include diff --git a/doc/how_to_guides/using_ompl_constrained_planning/src/ompl_constrained_planning_tutorial.cpp b/doc/how_to_guides/using_ompl_constrained_planning/src/ompl_constrained_planning_tutorial.cpp index 6541f7d0ad..5bc250b1df 100644 --- a/doc/how_to_guides/using_ompl_constrained_planning/src/ompl_constrained_planning_tutorial.cpp +++ b/doc/how_to_guides/using_ompl_constrained_planning/src/ompl_constrained_planning_tutorial.cpp @@ -1,7 +1,7 @@ #include -#include -#include +#include +#include #include #include #include diff --git a/doc/tutorials/pick_and_place_with_moveit_task_constructor/pick_and_place_with_moveit_task_constructor.rst b/doc/tutorials/pick_and_place_with_moveit_task_constructor/pick_and_place_with_moveit_task_constructor.rst index d88143f762..cf45286a90 100644 --- a/doc/tutorials/pick_and_place_with_moveit_task_constructor/pick_and_place_with_moveit_task_constructor.rst +++ b/doc/tutorials/pick_and_place_with_moveit_task_constructor/pick_and_place_with_moveit_task_constructor.rst @@ -115,8 +115,8 @@ Open ``mtc_node.cpp`` in your editor of choice, and paste in the following code. .. code-block:: c++ #include - #include - #include + #include + #include #include #include #include @@ -285,15 +285,15 @@ Open ``mtc_node.cpp`` in your editor of choice, and paste in the following code. The top of the code includes the ROS and MoveIt Libraries that this package uses. * ``rclcpp/rclcpp.hpp`` includes core ROS2 functionality - * ``moveit/planning_scene/planning_scene.h`` and ``moveit/planning_scene_interface/planning_scene_interface.h`` include functionality to interface with the robot model and collision objects + * ``moveit/planning_scene/planning_scene.hpp`` and ``moveit/planning_scene_interface/planning_scene_interface.hpp`` include functionality to interface with the robot model and collision objects * ``moveit/task_constructor/task.h``, ``moveit/task_constructor/solvers.h``, and ``moveit/task_constructor/stages.h`` include different components of MoveIt Task Constructor that are used in the example * ``tf2_geometry_msgs/tf2_geometry_msgs.hpp`` and ``tf2_eigen/tf2_eigen.hpp`` won't be used in this initial example, but they will be used for pose generation when we add more stages to the MoveIt Task Constructor task. .. code-block:: c++ #include - #include - #include + #include + #include #include #include #include diff --git a/doc/tutorials/pick_and_place_with_moveit_task_constructor/src/minimal.cpp b/doc/tutorials/pick_and_place_with_moveit_task_constructor/src/minimal.cpp index 8d53d0e8eb..4457b003aa 100644 --- a/doc/tutorials/pick_and_place_with_moveit_task_constructor/src/minimal.cpp +++ b/doc/tutorials/pick_and_place_with_moveit_task_constructor/src/minimal.cpp @@ -1,6 +1,6 @@ #include -#include -#include +#include +#include #include #include #include diff --git a/doc/tutorials/pick_and_place_with_moveit_task_constructor/src/mtc_node.cpp b/doc/tutorials/pick_and_place_with_moveit_task_constructor/src/mtc_node.cpp index c214b11617..f16374e97d 100644 --- a/doc/tutorials/pick_and_place_with_moveit_task_constructor/src/mtc_node.cpp +++ b/doc/tutorials/pick_and_place_with_moveit_task_constructor/src/mtc_node.cpp @@ -1,6 +1,6 @@ #include -#include -#include +#include +#include #include #include #include diff --git a/doc/tutorials/planning_around_objects/hello_moveit.cpp b/doc/tutorials/planning_around_objects/hello_moveit.cpp index ad2ccfed14..be617beffc 100644 --- a/doc/tutorials/planning_around_objects/hello_moveit.cpp +++ b/doc/tutorials/planning_around_objects/hello_moveit.cpp @@ -1,5 +1,5 @@ -#include -#include +#include +#include #include #include diff --git a/doc/tutorials/planning_around_objects/planning_around_objects.rst b/doc/tutorials/planning_around_objects/planning_around_objects.rst index ea3d0d7415..717f30ba72 100644 --- a/doc/tutorials/planning_around_objects/planning_around_objects.rst +++ b/doc/tutorials/planning_around_objects/planning_around_objects.rst @@ -19,7 +19,7 @@ At the top of your source file, add this to the list of includes: .. code-block:: C++ - #include + #include 2 Change the Target Pose ^^^^^^^^^^^^^^^^^^^^^^^^ diff --git a/doc/tutorials/visualizing_in_rviz/hello_moveit.cpp b/doc/tutorials/visualizing_in_rviz/hello_moveit.cpp index 4a8f710a34..3042fb6e02 100644 --- a/doc/tutorials/visualizing_in_rviz/hello_moveit.cpp +++ b/doc/tutorials/visualizing_in_rviz/hello_moveit.cpp @@ -1,4 +1,4 @@ -#include +#include #include #include diff --git a/doc/tutorials/your_first_project/kinova_hello_moveit.cpp b/doc/tutorials/your_first_project/kinova_hello_moveit.cpp index 804bf84427..95d74bfd58 100644 --- a/doc/tutorials/your_first_project/kinova_hello_moveit.cpp +++ b/doc/tutorials/your_first_project/kinova_hello_moveit.cpp @@ -1,7 +1,7 @@ #include #include -#include +#include int main(int argc, char* argv[]) { diff --git a/doc/tutorials/your_first_project/panda_hello_moveit.cpp b/doc/tutorials/your_first_project/panda_hello_moveit.cpp index 0cd93062f2..a7dc57f9fb 100644 --- a/doc/tutorials/your_first_project/panda_hello_moveit.cpp +++ b/doc/tutorials/your_first_project/panda_hello_moveit.cpp @@ -1,7 +1,7 @@ #include #include -#include +#include int main(int argc, char* argv[]) { diff --git a/doc/tutorials/your_first_project/your_first_project.rst b/doc/tutorials/your_first_project/your_first_project.rst index 2c15798feb..5b45a70f96 100644 --- a/doc/tutorials/your_first_project/your_first_project.rst +++ b/doc/tutorials/your_first_project/your_first_project.rst @@ -51,7 +51,7 @@ This first block of code is a bit of boilerplate but you should be used to seein #include #include - #include + #include int main(int argc, char * argv[]) {