Skip to content

Commit cdee39b

Browse files
Enhancement/use hpp for headers based on PR moveit/moveit2#3113 (#997)
1 parent 8134bc7 commit cdee39b

File tree

32 files changed

+115
-114
lines changed

32 files changed

+115
-114
lines changed

doc/examples/collision_environments/src/collision_scene_example.cpp

+6-6
Original file line numberDiff line numberDiff line change
@@ -1,12 +1,12 @@
11
#include <rclcpp/rclcpp.hpp>
22

33
// MoveIt
4-
#include <moveit/common_planning_interface_objects/common_objects.h>
5-
#include <moveit/kinematic_constraints/utils.h>
6-
#include <moveit/move_group_interface/move_group_interface.h>
7-
#include <moveit/planning_scene/planning_scene.h>
8-
#include <moveit/planning_scene_interface/planning_scene_interface.h>
9-
#include <moveit/robot_model_loader/robot_model_loader.h>
4+
#include <moveit/common_planning_interface_objects/common_objects.hpp>
5+
#include <moveit/kinematic_constraints/utils.hpp>
6+
#include <moveit/move_group_interface/move_group_interface.hpp>
7+
#include <moveit/planning_scene/planning_scene.hpp>
8+
#include <moveit/planning_scene_interface/planning_scene_interface.hpp>
9+
#include <moveit/robot_model_loader/robot_model_loader.hpp>
1010
// TF2
1111
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
1212

doc/examples/hybrid_planning/hybrid_planning_tutorial.rst

+5-5
Original file line numberDiff line numberDiff line change
@@ -100,7 +100,7 @@ The dataflow within the component can be seen in the picture below:
100100
.. image:: images/global_planner_dataflow.png
101101
:width: 500pt
102102

103-
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 <moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_interface.h>`:
103+
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 <moveit_ros/hybrid_planning/global_planner/global_planner_component/include/moveit/global_planner/global_planner_interface.hpp>`:
104104

105105
.. code-block:: c++
106106

@@ -140,7 +140,7 @@ Via the *Global Solution Subscriber* the *Local Planner Component* receives glob
140140

141141
The behavior of the *Local Planner Component* can be customized via the *Trajectory Operator Plugin* and the local *Solver Plugin*:
142142

143-
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 <moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/trajectory_operator_interface.h>`:
143+
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 <moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/trajectory_operator_interface.hpp>`:
144144

145145
.. code-block:: c++
146146

@@ -174,7 +174,7 @@ The *Trajectory Operator Plugin* handles the reference trajectory. To create you
174174

175175
*Trajectory Operator* example implementations can be found :moveit_codedir:`here <moveit_ros/hybrid_planning/local_planner/trajectory_operator_plugins/>`.
176176

177-
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 <moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_constraint_solver_interface.h>`:
177+
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 <moveit_ros/hybrid_planning/local_planner/local_planner_component/include/moveit/local_planner/local_constraint_solver_interface.hpp>`:
178178

179179
.. code-block:: c++
180180

@@ -238,7 +238,7 @@ The callback function an event channel in the *Hybrid Planning Manager* looks li
238238
}
239239
};
240240

241-
To create you own *Planner Logic Plugin* you need inherit from the :moveit_codedir:`PlannerLogicInterface <moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/planner_logic_interface.h>`:
241+
To create you own *Planner Logic Plugin* you need inherit from the :moveit_codedir:`PlannerLogicInterface <moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/planner_logic_interface.hpp>`:
242242

243243
.. code-block:: c++
244244

@@ -259,4 +259,4 @@ To create you own *Planner Logic Plugin* you need inherit from the :moveit_coded
259259
ReactionResult react(const std::string& event) override;
260260
};
261261

262-
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<moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/planner_logic_interface.h>`.
262+
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<moveit_ros/hybrid_planning/hybrid_planning_manager/hybrid_planning_manager_component/include/moveit/hybrid_planning_manager/planner_logic_interface.hpp>`.

doc/examples/motion_planning_api/src/motion_planning_api_tutorial.cpp

+11-11
Original file line numberDiff line numberDiff line change
@@ -37,14 +37,14 @@
3737
#include <pluginlib/class_loader.hpp>
3838

3939
// MoveIt
40-
#include <moveit/robot_model_loader/robot_model_loader.h>
41-
#include <moveit/planning_interface/planning_interface.h>
42-
#include <moveit/planning_scene/planning_scene.h>
43-
#include <moveit/kinematic_constraints/utils.h>
40+
#include <moveit/robot_model_loader/robot_model_loader.hpp>
41+
#include <moveit/planning_interface/planning_interface.hpp>
42+
#include <moveit/planning_scene/planning_scene.hpp>
43+
#include <moveit/kinematic_constraints/utils.hpp>
4444
#include <moveit_msgs/msg/display_trajectory.hpp>
45-
#include <moveit_msgs/msg/planning_scene.h>
45+
#include <moveit_msgs/msg/planning_scene.hpp>
4646
#include <moveit_visual_tools/moveit_visual_tools.h>
47-
#include <moveit/move_group_interface/move_group_interface.h>
47+
#include <moveit/move_group_interface/move_group_interface.hpp>
4848

4949
static const rclcpp::Logger LOGGER = rclcpp::get_logger("motion_planning_api_tutorial");
5050

@@ -68,10 +68,10 @@ int main(int argc, char** argv)
6868
// interface to load any planner that you want to use. Before we can
6969
// load the planner, we need two objects, a RobotModel and a
7070
// PlanningScene. We will start by instantiating a
71-
// :moveit_codedir:`RobotModelLoader<moveit_ros/planning/robot_model_loader/include/moveit/robot_model_loader/robot_model_loader.h>`
71+
// :moveit_codedir:`RobotModelLoader<moveit_ros/planning/robot_model_loader/include/moveit/robot_model_loader/robot_model_loader.hpp>`
7272
// object, which will look up the robot description on the ROS
7373
// parameter server and construct a
74-
// :moveit_codedir:`RobotModel<moveit_core/robot_model/include/moveit/robot_model/robot_model.h>`
74+
// :moveit_codedir:`RobotModel<moveit_core/robot_model/include/moveit/robot_model/robot_model.hpp>`
7575
// for us to use.
7676
const std::string PLANNING_GROUP = "panda_arm";
7777
robot_model_loader::RobotModelLoader robot_model_loader(motion_planning_api_tutorial_node, "robot_description");
@@ -81,9 +81,9 @@ int main(int argc, char** argv)
8181
const moveit::core::JointModelGroup* joint_model_group = robot_state->getJointModelGroup(PLANNING_GROUP);
8282

8383
// Using the
84-
// :moveit_codedir:`RobotModel<moveit_core/robot_model/include/moveit/robot_model/robot_model.h>`,
84+
// :moveit_codedir:`RobotModel<moveit_core/robot_model/include/moveit/robot_model/robot_model.hpp>`,
8585
// we can construct a
86-
// :moveit_codedir:`PlanningScene<moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h>`
86+
// :moveit_codedir:`PlanningScene<moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.hpp>`
8787
// that maintains the state of the world (including the robot).
8888
planning_scene::PlanningScenePtr planning_scene(new planning_scene::PlanningScene(robot_model));
8989

@@ -186,7 +186,7 @@ int main(int argc, char** argv)
186186

187187
// We will create the request as a constraint using a helper function available
188188
// from the
189-
// :moveit_codedir:`kinematic_constraints<moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/kinematic_constraint.h>`
189+
// :moveit_codedir:`kinematic_constraints<moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/kinematic_constraint.hpp>`
190190
// package.
191191
moveit_msgs::msg::Constraints pose_goal =
192192
kinematic_constraints::constructGoalConstraints("panda_link8", pose, tolerance_pose, tolerance_angle);

doc/examples/motion_planning_pipeline/src/motion_planning_pipeline_tutorial.cpp

+9-9
Original file line numberDiff line numberDiff line change
@@ -37,12 +37,12 @@
3737
#include <pluginlib/class_loader.hpp>
3838

3939
// MoveIt
40-
#include <moveit/robot_model_loader/robot_model_loader.h>
41-
#include <moveit/robot_state/conversions.h>
42-
#include <moveit/planning_pipeline/planning_pipeline.h>
43-
#include <moveit/planning_interface/planning_interface.h>
44-
#include <moveit/planning_scene_monitor/planning_scene_monitor.h>
45-
#include <moveit/kinematic_constraints/utils.h>
40+
#include <moveit/robot_model_loader/robot_model_loader.hpp>
41+
#include <moveit/robot_state/conversions.hpp>
42+
#include <moveit/planning_pipeline/planning_pipeline.hpp>
43+
#include <moveit/planning_interface/planning_interface.hpp>
44+
#include <moveit/planning_scene_monitor/planning_scene_monitor.hpp>
45+
#include <moveit/kinematic_constraints/utils.hpp>
4646
#include <moveit_msgs/msg/display_trajectory.hpp>
4747
#include <moveit_msgs/msg/planning_scene.hpp>
4848
#include <moveit_visual_tools/moveit_visual_tools.h>
@@ -67,10 +67,10 @@ int main(int argc, char** argv)
6767
// a RobotModel and a PlanningScene.
6868
//
6969
// We will start by instantiating a
70-
// :moveit_codedir:`RobotModelLoader<moveit_ros/planning/robot_model_loader/include/moveit/robot_model_loader/robot_model_loader.h>`
70+
// :moveit_codedir:`RobotModelLoader<moveit_ros/planning/robot_model_loader/include/moveit/robot_model_loader/robot_model_loader.hpp>`
7171
// object, which will look up the robot description on the ROS
7272
// parameter server and construct a
73-
// :moveit_codedir:`RobotModel<moveit_core/robot_model/include/moveit/robot_model/robot_model.h>`
73+
// :moveit_codedir:`RobotModel<moveit_core/robot_model/include/moveit/robot_model/robot_model.hpp>`
7474
// for us to use.
7575
robot_model_loader::RobotModelLoaderPtr robot_model_loader(
7676
new robot_model_loader::RobotModelLoader(node, "robot_description"));
@@ -158,7 +158,7 @@ int main(int argc, char** argv)
158158

159159
// We will create the request as a constraint using a helper
160160
// function available from the
161-
// :moveit_codedir:`kinematic_constraints<moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/kinematic_constraint.h>`
161+
// :moveit_codedir:`kinematic_constraints<moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/kinematic_constraint.hpp>`
162162
// package.
163163
req.group_name = "panda_arm";
164164
moveit_msgs::msg::Constraints pose_goal =

doc/examples/move_group_interface/move_group_interface_tutorial.rst

+1-1
Original file line numberDiff line numberDiff line change
@@ -5,7 +5,7 @@ Move Group C++ Interface
55
.. image:: move_group_interface_tutorial_start_screen.png
66
:width: 700px
77

8-
In MoveIt, the simplest user interface is through the :moveit_codedir:`MoveGroupInterface<moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h>` class.
8+
In MoveIt, the simplest user interface is through the :moveit_codedir:`MoveGroupInterface<moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.hpp>` class.
99
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.
1010
This interface communicates over ROS topics, services, and actions to the :moveit_codedir:`MoveGroup<moveit_ros/move_group/src/move_group.cpp>` node.
1111

doc/examples/move_group_interface/src/move_group_interface_tutorial.cpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -34,8 +34,8 @@
3434

3535
/* Author: Sachin Chitta, Dave Coleman, Mike Lautman */
3636

37-
#include <moveit/move_group_interface/move_group_interface.h>
38-
#include <moveit/planning_scene_interface/planning_scene_interface.h>
37+
#include <moveit/move_group_interface/move_group_interface.hpp>
38+
#include <moveit/planning_scene_interface/planning_scene_interface.hpp>
3939

4040
#include <moveit_msgs/msg/display_robot_state.hpp>
4141
#include <moveit_msgs/msg/display_trajectory.hpp>
@@ -74,12 +74,12 @@ int main(int argc, char** argv)
7474
static const std::string PLANNING_GROUP = "panda_arm";
7575

7676
// The
77-
// :moveit_codedir:`MoveGroupInterface<moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.h>`
77+
// :moveit_codedir:`MoveGroupInterface<moveit_ros/planning_interface/move_group_interface/include/moveit/move_group_interface/move_group_interface.hpp>`
7878
// class can be easily set up using just the name of the planning group you would like to control and plan for.
7979
moveit::planning_interface::MoveGroupInterface move_group(move_group_node, PLANNING_GROUP);
8080

8181
// We will use the
82-
// :moveit_codedir:`PlanningSceneInterface<moveit_ros/planning_interface/planning_scene_interface/include/moveit/planning_scene_interface/planning_scene_interface.h>`
82+
// :moveit_codedir:`PlanningSceneInterface<moveit_ros/planning_interface/planning_scene_interface/include/moveit/planning_scene_interface/planning_scene_interface.hpp>`
8383
// class to add and remove collision objects in our "virtual world" scene
8484
moveit::planning_interface::PlanningSceneInterface planning_scene_interface;
8585

doc/examples/moveit_cpp/src/moveit_cpp_tutorial.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -1,8 +1,8 @@
11
#include <rclcpp/rclcpp.hpp>
22
#include <memory>
33
// MoveitCpp
4-
#include <moveit/moveit_cpp/moveit_cpp.h>
5-
#include <moveit/moveit_cpp/planning_component.h>
4+
#include <moveit/moveit_cpp/moveit_cpp.hpp>
5+
#include <moveit/moveit_cpp/planning_component.hpp>
66

77
#include <geometry_msgs/msg/point_stamped.h>
88

doc/examples/planning_scene/planning_scene_tutorial.rst

+1-1
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
Planning Scene
22
==================================
33

4-
The :moveit_codedir:`PlanningScene<moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h>` class provides the main interface that you will use
4+
The :moveit_codedir:`PlanningScene<moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.hpp>` class provides the main interface that you will use
55
for collision checking and constraint checking. In this tutorial, we
66
will explore the C++ interface to this class.
77

doc/examples/planning_scene/src/planning_scene_tutorial.cpp

+11-11
Original file line numberDiff line numberDiff line change
@@ -1,10 +1,10 @@
11
#include <rclcpp/rclcpp.hpp>
22

33
// MoveIt
4-
#include <moveit/robot_model_loader/robot_model_loader.h>
5-
#include <moveit/planning_scene/planning_scene.h>
4+
#include <moveit/robot_model_loader/robot_model_loader.hpp>
5+
#include <moveit/planning_scene/planning_scene.hpp>
66

7-
#include <moveit/kinematic_constraints/utils.h>
7+
#include <moveit/kinematic_constraints/utils.hpp>
88

99
// BEGIN_SUB_TUTORIAL stateFeasibilityTestExample
1010
//
@@ -38,12 +38,12 @@ int main(int argc, char** argv)
3838
// Setup
3939
// ^^^^^
4040
//
41-
// The :moveit_codedir:`PlanningScene<moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.h>`
41+
// The :moveit_codedir:`PlanningScene<moveit_core/planning_scene/include/moveit/planning_scene/planning_scene.hpp>`
4242
// class can be easily setup and configured using a
43-
// :moveit_codedir:`RobotModel<moveit_core/robot_model/include/moveit/robot_model/robot_model.h>`
43+
// :moveit_codedir:`RobotModel<moveit_core/robot_model/include/moveit/robot_model/robot_model.hpp>`
4444
// or a URDF and SRDF. This is, however, not the recommended way to instantiate a
4545
// PlanningScene. The
46-
// :moveit_codedir:`PlanningSceneMonitor<moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.h>`
46+
// :moveit_codedir:`PlanningSceneMonitor<moveit_ros/planning/planning_scene_monitor/include/moveit/planning_scene_monitor/planning_scene_monitor.hpp>`
4747
// is the recommended method to create and maintain the current
4848
// planning scene (and is discussed in detail in the next tutorial)
4949
// using data from the robot's joints and the sensors on the robot. In
@@ -64,9 +64,9 @@ int main(int argc, char** argv)
6464
// current state is in *self-collision*, i.e. whether the current
6565
// configuration of the robot would result in the robot's parts
6666
// hitting each other. To do this, we will construct a
67-
// :moveit_codedir:`CollisionRequest<moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h>`
67+
// :moveit_codedir:`CollisionRequest<moveit_core/collision_detection/include/moveit/collision_detection/collision_common.hpp>`
6868
// object and a
69-
// :moveit_codedir:`CollisionResult<moveit_core/collision_detection/include/moveit/collision_detection/collision_common.h>`
69+
// :moveit_codedir:`CollisionResult<moveit_core/collision_detection/include/moveit/collision_detection/collision_common.hpp>`
7070
// object and pass them
7171
// into the collision checking function. Note that the result of
7272
// whether the robot is in self-collision or not is contained within
@@ -151,7 +151,7 @@ int main(int argc, char** argv)
151151
// ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
152152
//
153153
// The
154-
// :moveit_codedir:`AllowedCollisionMatrix<moveit_core/collision_detection/include/moveit/collision_detection/collision_matrix.h>`
154+
// :moveit_codedir:`AllowedCollisionMatrix<moveit_core/collision_detection/include/moveit/collision_detection/collision_matrix.hpp>`
155155
// (ACM)
156156
// provides a mechanism to tell the collision world to ignore
157157
// collisions between certain object: both parts of the robot and
@@ -200,7 +200,7 @@ int main(int argc, char** argv)
200200
// The PlanningScene class also includes easy to use function calls
201201
// for checking constraints. The constraints can be of two types:
202202
// (a) constraints chosen from the
203-
// :moveit_codedir:`KinematicConstraint<moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/kinematic_constraint.h>`
203+
// :moveit_codedir:`KinematicConstraint<moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/kinematic_constraint.hpp>`
204204
// set: i.e. JointConstraint, PositionConstraint, OrientationConstraint and
205205
// VisibilityConstraint and (b) user
206206
// defined constraints specified through a callback. We will first
@@ -213,7 +213,7 @@ int main(int argc, char** argv)
213213
// on the end-effector of the panda_arm group of the Panda robot. Note the
214214
// use of convenience functions for filling up the constraints
215215
// (these functions are found in the
216-
// :moveit_codedir:`utils.h<moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/utils.h>`
216+
// :moveit_codedir:`utils.h<moveit_core/kinematic_constraints/include/moveit/kinematic_constraints/utils.hpp>`
217217
// file from the
218218
// kinematic_constraints directory in moveit_core).
219219

0 commit comments

Comments
 (0)