Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Reordered code execution #516

Open
wants to merge 2 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
Expand Up @@ -56,10 +56,6 @@ int main(int argc, char** argv)
std::shared_ptr<rclcpp::Node> 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
// ^^^^^
Expand All @@ -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<moveit_core/robot_model/include/moveit/robot_model/robot_model.h>`,
// we can construct a
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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
// ^^^^^
Expand Down Expand Up @@ -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(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -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
Expand All @@ -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<moveit_ros/planning_interface/planning_scene_interface/include/moveit/planning_scene_interface/planning_scene_interface.h>`
// class to add and remove collision objects in our "virtual world" scene
Expand Down