fix last merge
This commit is contained in:
parent
e46c7bef74
commit
2019e7db41
5 changed files with 66 additions and 31 deletions
|
@ -3,12 +3,11 @@ from launch import LaunchDescription
|
|||
from launch.actions import (
|
||||
DeclareLaunchArgument,
|
||||
IncludeLaunchDescription,
|
||||
OpaqueFunction,
|
||||
RegisterEventHandler,
|
||||
RegisterEventHandler
|
||||
)
|
||||
from ament_index_python.packages import get_package_share_directory, get_package_share_path
|
||||
from launch.conditions import IfCondition, UnlessCondition
|
||||
from launch.event_handlers import OnProcessExit
|
||||
from launch.event_handlers import OnProcessExit, OnExecutionComplete
|
||||
from launch.launch_description_sources import PythonLaunchDescriptionSource
|
||||
from launch.substitutions import Command, FindExecutable, LaunchConfiguration, PathJoinSubstitution
|
||||
from launch_ros.actions import Node
|
||||
|
@ -161,7 +160,6 @@ def generate_launch_description():
|
|||
[FindPackageShare("sdf_models"), "worlds", "empty_world.sdf"] # TODO тут пакет извне должен задаваться
|
||||
)
|
||||
|
||||
print(world_config_file)
|
||||
robot_description_content = Command(
|
||||
[
|
||||
PathJoinSubstitution([FindExecutable(name="xacro")]),
|
||||
|
@ -262,9 +260,6 @@ def generate_launch_description():
|
|||
[FindPackageShare(moveit_config_package), "config", "kinematics.yaml"]
|
||||
)
|
||||
|
||||
# robot_description_planning = {
|
||||
# "robot_description_planning": load_yaml_abs(str(joint_limit_params.perform(context)))
|
||||
# }
|
||||
|
||||
# Planning Configuration
|
||||
ompl_planning_pipeline_config = {
|
||||
|
@ -314,7 +309,6 @@ def generate_launch_description():
|
|||
robot_description,
|
||||
robot_description_semantic,
|
||||
robot_description_kinematics,
|
||||
# robot_description_planning,
|
||||
ompl_planning_pipeline_config,
|
||||
trajectory_execution,
|
||||
moveit_controllers,
|
||||
|
@ -334,7 +328,6 @@ def generate_launch_description():
|
|||
robot_description_semantic,
|
||||
ompl_planning_pipeline_config,
|
||||
robot_description_kinematics,
|
||||
# robot_description_planning,
|
||||
],
|
||||
condition=IfCondition(launch_rviz),
|
||||
)
|
||||
|
@ -347,7 +340,6 @@ def generate_launch_description():
|
|||
robot_description,
|
||||
robot_description_semantic,
|
||||
robot_description_kinematics,
|
||||
# robot_description_planning,
|
||||
ompl_planning_pipeline_config,
|
||||
trajectory_execution,
|
||||
moveit_controllers,
|
||||
|
@ -364,7 +356,6 @@ def generate_launch_description():
|
|||
robot_description,
|
||||
robot_description_semantic,
|
||||
robot_description_kinematics,
|
||||
# robot_description_planning,
|
||||
ompl_planning_pipeline_config,
|
||||
trajectory_execution,
|
||||
moveit_controllers,
|
||||
|
@ -383,7 +374,7 @@ def generate_launch_description():
|
|||
gazebo_spawn_robot,
|
||||
move_group_node,
|
||||
move_topose_action_server,
|
||||
move_cartesian_path_action_server
|
||||
move_cartesian_path_action_server,
|
||||
]
|
||||
|
||||
return LaunchDescription(declared_arguments + nodes_to_start)
|
Loading…
Add table
Add a link
Reference in a new issue