ROS Components for hexapod_robot
Du kan inte välja fler än 25 ämnen Ämnen måste starta med en bokstav eller siffra, kan innehålla bindestreck ('-') och vara max 35 tecken långa.

85 lines
2.8KB

  1. from launch import LaunchDescription
  2. from launch.actions import RegisterEventHandler
  3. from launch.substitutions import Command, FindExecutable, LaunchConfiguration, PathJoinSubstitution
  4. from launch.event_handlers import OnProcessExit
  5. from launch_ros.actions import Node
  6. from launch_ros.substitutions import FindPackageShare
  7. from moveit_configs_utils import MoveItConfigsBuilder
  8. def generate_launch_description():
  9. moveit_config = (
  10. MoveItConfigsBuilder("hexapod_robot", package_name = "hexapod_robot")
  11. .planning_scene_monitor(
  12. publish_robot_description=True, publish_robot_description_semantic=True
  13. )
  14. .planning_pipelines(pipelines = ["ompl"])
  15. .to_moveit_configs()
  16. )
  17. move_group_node = Node(
  18. package = "moveit_ros_move_group",
  19. executable = "move_group",
  20. output = "screen",
  21. parameters = [moveit_config.to_dict()]
  22. )
  23. ros2_controllers = PathJoinSubstitution([FindPackageShare("hexapod_robot"), "config", "ros2_controllers.yaml"])
  24. robot_state_publisher_node = Node(
  25. package = "robot_state_publisher",
  26. executable = "robot_state_publisher",
  27. parameters = [moveit_config.robot_description],
  28. output = "both"
  29. )
  30. ros2_control_node = Node(
  31. package = "controller_manager",
  32. executable = "ros2_control_node",
  33. parameters = [moveit_config.robot_description, ros2_controllers],
  34. output="both"
  35. )
  36. joint_state_broadcaster_spawner = Node (
  37. package = "controller_manager",
  38. executable = "spawner",
  39. arguments = ["joint_state_broadcaster", "--controller-manager", "/controller_manager"]
  40. )
  41. joint_trajectory_controller_spawner = Node(
  42. package = "controller_manager",
  43. executable = "spawner",
  44. arguments = ["e1_group_controller", "e2_group_controller", "e3_group_controller", "e4_group_controller", "e5_group_controller", "e6_group_controller", "--controller-manager", "/controller_manager"]
  45. )
  46. delay_rviz_after_joint_state_broadcaster_spawner = RegisterEventHandler(
  47. event_handler = OnProcessExit(
  48. target_action = joint_state_broadcaster_spawner,
  49. on_exit = [rviz_node]
  50. )
  51. )
  52. delay_joint_trajectory_controller_spawner_after_joint_state_broadcaster_spawner = RegisterEventHandler(
  53. event_handler = OnProcessExit(
  54. target_action = joint_state_broadcaster_spawner,
  55. on_exit = [joint_trajectory_controller_spawner]
  56. )
  57. )
  58. nodes = [
  59. robot_state_publisher_node,
  60. move_group_node,
  61. ros2_control_node,
  62. joint_state_broadcaster_spawner,
  63. delay_joint_trajectory_controller_spawner_after_joint_state_broadcaster_spawner
  64. ]
  65. return LaunchDescription(nodes)