Skip to content

Commit

Permalink
Remove param declarations, rename demo_controller file and fix launch…
Browse files Browse the repository at this point in the history
… file
  • Loading branch information
sjahr committed Oct 19, 2021
1 parent d506f3a commit a371886
Show file tree
Hide file tree
Showing 3 changed files with 11 additions and 17 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -53,21 +53,6 @@ const std::string UNDEFINED = "<undefined>";

bool MoveItPlanningPipeline::initialize(const rclcpp::Node::SharedPtr& node)
{
// Declare planning_scene_monitor parameter
node->declare_parameter<std::string>(PLANNING_SCENE_MONITOR_NS + "name", std::string("planning_scene_monitor"));
node->declare_parameter<std::string>(PLANNING_SCENE_MONITOR_NS + "robot_description",
std::string("robot_description"));
node->declare_parameter<std::string>(PLANNING_SCENE_MONITOR_NS + "joint_state_topic",
planning_scene_monitor::PlanningSceneMonitor::DEFAULT_JOINT_STATES_TOPIC);
node->declare_parameter<std::string>(
PLANNING_SCENE_MONITOR_NS + "attached_collision_object_topic",
planning_scene_monitor::PlanningSceneMonitor::DEFAULT_ATTACHED_COLLISION_OBJECT_TOPIC);
node->declare_parameter<std::string>(PLANNING_SCENE_MONITOR_NS + "monitored_planning_scene_topic",
planning_scene_monitor::PlanningSceneMonitor::MONITORED_PLANNING_SCENE_TOPIC);
node->declare_parameter<std::string>(PLANNING_SCENE_MONITOR_NS + "publish_planning_scene_topic",
planning_scene_monitor::PlanningSceneMonitor::DEFAULT_PLANNING_SCENE_TOPIC);
node->declare_parameter<double>(PLANNING_SCENE_MONITOR_NS + "wait_for_initial_state_timeout", 0.0);

// Declare planning pipeline paramter
node->declare_parameter<std::vector<std::string>>(PLANNING_PIPELINES_NS + "pipeline_names",
std::vector<std::string>({ "ompl" }));
Expand All @@ -88,7 +73,6 @@ bool MoveItPlanningPipeline::initialize(const rclcpp::Node::SharedPtr& node)

// Initialize MoveItCpp API
moveit_cpp_ = std::make_shared<moveit_cpp::MoveItCpp>(node);

return true;
}

Expand Down
12 changes: 11 additions & 1 deletion moveit_ros/hybrid_planning/test/launch/hybrid_planning.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -65,6 +65,14 @@ def generate_launch_description():
)
ompl_planning_pipeline_config["ompl"].update(ompl_planning_yaml)

moveit_simple_controllers_yaml = load_yaml(
"moveit_resources_panda_moveit_config", "config/panda_controllers.yaml"
)
moveit_controllers = {
"moveit_simple_controller_manager": moveit_simple_controllers_yaml,
"moveit_controller_manager": "moveit_simple_controller_manager/MoveItSimpleControllerManager",
}

global_planner_param = load_yaml(
"moveit_hybrid_planning", "config/global_planner.yaml"
)
Expand Down Expand Up @@ -92,6 +100,7 @@ def generate_launch_description():
robot_description_semantic,
kinematics_yaml,
ompl_planning_pipeline_config,
moveit_controllers,
],
),
ComposableNode(
Expand Down Expand Up @@ -153,6 +162,7 @@ def generate_launch_description():
"config",
"demo_controller.yaml",
)

ros2_control_node = Node(
package="controller_manager",
executable="ros2_control_node",
Expand All @@ -171,7 +181,7 @@ def generate_launch_description():
]:
load_controllers += [
ExecuteProcess(
cmd=["ros2 run controller_manager spawner {}".format(controller)],
cmd=["ros2 run controller_manager spawner.py {}".format(controller)],
shell=True,
output="screen",
)
Expand Down

0 comments on commit a371886

Please sign in to comment.