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 498056314a..9ba519d61d 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 @@ -56,10 +56,6 @@ int main(int argc, char** argv) std::shared_ptr motion_planning_api_tutorial_node = rclcpp::Node::make_shared("motion_planning_api_tutorial", node_options); - rclcpp::executors::SingleThreadedExecutor executor; - executor.add_node(motion_planning_api_tutorial_node); - std::thread([&executor]() { executor.spin(); }).detach(); - // BEGIN_TUTORIAL // Start // ^^^^^ @@ -80,6 +76,12 @@ int main(int argc, char** argv) moveit::core::RobotStatePtr robot_state(new moveit::core::RobotState(robot_model)); const moveit::core::JointModelGroup* joint_model_group = robot_state->getJointModelGroup(PLANNING_GROUP); + // We spin up a SingleThreadedExecutor for the current state monitor to get information + // about the robot's state. + rclcpp::executors::SingleThreadedExecutor executor; + executor.add_node(motion_planning_api_tutorial_node); + std::thread([&executor]() { executor.spin(); }).detach(); + // Using the // :moveit_codedir:`RobotModel`, // we can construct a 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 0a5706f48a..e8501249bd 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 @@ -56,10 +56,6 @@ int main(int argc, char** argv) node_options.automatically_declare_parameters_from_overrides(true); auto node = rclcpp::Node::make_shared("motion_planning_pipeline_tutorial", node_options); - rclcpp::executors::SingleThreadedExecutor executor; - executor.add_node(node); - std::thread([&executor]() { executor.spin(); }).detach(); - // BEGIN_TUTORIAL // Start // ^^^^^ @@ -105,6 +101,12 @@ int main(int argc, char** argv) group is useful for dealing with one set of joints at a time such as a left arm or a end effector */ const moveit::core::JointModelGroup* joint_model_group = robot_state->getJointModelGroup("panda_arm"); + // We spin up a SingleThreadedExecutor for the current state monitor to get information + // about the robot's state. + rclcpp::executors::SingleThreadedExecutor executor; + executor.add_node(node); + std::thread([&executor]() { executor.spin(); }).detach(); + // We can now setup the PlanningPipeline 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/examples/move_group_interface/src/move_group_interface_tutorial.cpp b/doc/examples/move_group_interface/src/move_group_interface_tutorial.cpp index f3bb4951e1..e8bf1ba1d7 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 @@ -57,12 +57,6 @@ int main(int argc, char** argv) node_options.automatically_declare_parameters_from_overrides(true); auto move_group_node = rclcpp::Node::make_shared("move_group_interface_tutorial", node_options); - // We spin up a SingleThreadedExecutor for the current state monitor to get information - // about the robot's state. - rclcpp::executors::SingleThreadedExecutor executor; - executor.add_node(move_group_node); - std::thread([&executor]() { executor.spin(); }).detach(); - // BEGIN_TUTORIAL // // Setup @@ -78,6 +72,12 @@ int main(int argc, char** argv) // 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 spin up a SingleThreadedExecutor for the current state monitor to get information + // about the robot's state. + rclcpp::executors::SingleThreadedExecutor executor; + executor.add_node(move_group_node); + std::thread([&executor]() { executor.spin(); }).detach(); + // We will use the // :moveit_codedir:`PlanningSceneInterface` // class to add and remove collision objects in our "virtual world" scene