From 665b981ce189c594c7bee9d0839f93a3a7fe5b36 Mon Sep 17 00:00:00 2001 From: Marcus Grieger Date: Sun, 4 Feb 2024 19:10:07 +0100 Subject: [PATCH] Added moveit stuff --- .setup_assistant | 10 + CMakeLists.txt | 13 +- bringup/config/controllers.yaml | 58 -- bringup/config/hexapod_robot.rviz | 327 --------- config/hexapod_robot.rviz | 669 ++++++++++++++++++ config/hexapod_robot.srdf | 21 + config/joint_limits.yaml | 7 + config/kinematics.yaml | 77 ++ config/moveit_controllers.yaml | 81 +++ config/pilz_cartesian_limits.yaml | 6 + config/ros2_controllers.yaml | 103 +++ .../urdf/hexapod_robot.urdf.xacro | 6 +- .../urdf/hexapod_robot_macros.xacro | 6 +- .../urdf/hexapod_robot_materials.xacro | 0 .../urdf/hexapod_robot_ros2_control.xacro | 12 +- kinematics/hexapod_robot_ik_service.cpp | 4 +- .../launch => launch}/hexapod_robot.launch.py | 15 +- .../hexapod_robot_gui.launch.py | 60 +- package.xml | 4 + srv/HexapodRobotInverseKinematics.srv | 5 +- 20 files changed, 1039 insertions(+), 445 deletions(-) create mode 100644 .setup_assistant delete mode 100644 bringup/config/controllers.yaml delete mode 100644 bringup/config/hexapod_robot.rviz create mode 100644 config/hexapod_robot.rviz create mode 100644 config/hexapod_robot.srdf create mode 100644 config/joint_limits.yaml create mode 100644 config/kinematics.yaml create mode 100644 config/moveit_controllers.yaml create mode 100644 config/pilz_cartesian_limits.yaml create mode 100644 config/ros2_controllers.yaml rename {description => config}/urdf/hexapod_robot.urdf.xacro (78%) rename {description => config}/urdf/hexapod_robot_macros.xacro (96%) rename {description => config}/urdf/hexapod_robot_materials.xacro (100%) rename {description => config}/urdf/hexapod_robot_ros2_control.xacro (94%) rename {bringup/launch => launch}/hexapod_robot.launch.py (88%) rename {bringup/launch => launch}/hexapod_robot_gui.launch.py (61%) diff --git a/.setup_assistant b/.setup_assistant new file mode 100644 index 0000000..b450ed8 --- /dev/null +++ b/.setup_assistant @@ -0,0 +1,10 @@ +moveit_setup_assistant_config: + urdf: + package: hexapod_robot + relative_path: config/urdf/hexapod_robot.urdf.xacro + srdf: + relative_path: config/hexapod_robot.srdf + package_settings: + author_name: Marcus Grieger + author_email: marcus@grieger.xyz + generated_timestamp: 1707046355 \ No newline at end of file diff --git a/CMakeLists.txt b/CMakeLists.txt index 0a26f37..4a22b66 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -11,6 +11,8 @@ find_package(hardware_interface REQUIRED) find_package(pluginlib REQUIRED) find_package(rclcpp REQUIRED) find_package(rclcpp_lifecycle REQUIRED) + +find_package(geometry_msgs REQUIRED) find_package(rosidl_default_generators REQUIRED) # Build hexapod_robot_interfaces @@ -21,6 +23,7 @@ set(srv_files rosidl_generate_interfaces(${PROJECT_NAME} ${srv_files} + DEPENDENCIES geometry_msgs ) # Build hexapod_robot_ik_server @@ -70,17 +73,17 @@ pluginlib_export_plugin_description_file(hardware_interface hexapod_robot.xml) install( - DIRECTORY description - DESTINATION share/hexapod_robot + DIRECTORY config launch + DESTINATION share/${PROJECT_NAME} ) install( - DIRECTORY bringup/launch bringup/config - DESTINATION share/hexapod_robot + FILES .setup_assistant DESTINATION share/${PROJECT_NAME} ) + install(TARGETS hexapod_robot_ik_server - DESTINATION lib/hexapod_robot + DESTINATION lib/${PROJECT_NAME} ) install(TARGETS hexapod_robot_hwi diff --git a/bringup/config/controllers.yaml b/bringup/config/controllers.yaml deleted file mode 100644 index 2ec8177..0000000 --- a/bringup/config/controllers.yaml +++ /dev/null @@ -1,58 +0,0 @@ -controller_manager: - ros__parameters: - update_rate: 50 - - joint_state_broadcaster: - type: joint_state_broadcaster/JointStateBroadcaster - - joint_trajectory_controller: - type: joint_trajectory_controller/JointTrajectoryController - - forward_position_controller: - type: forward_command_controller/ForwardCommandController - - - -forward_position_controller: - ros__parameters: - joints: - - t3_joint - interface_name: position - -joint_trajectory_controller: - ros__parameters: - joints: - - c1_joint - - f1_joint - - t1_joint - - - c2_joint - - f2_joint - - t2_joint - - - c3_joint - - f3_joint - - t3_joint - - - c4_joint - - f4_joint - - t4_joint - - - c5_joint - - f5_joint - - t5_joint - - - c6_joint - - f6_joint - - t6_joint - - command_interfaces: - - position - - state_interfaces: - - position - - action_monitor_rate: 20.0 - - allow_partial_joints_goal: false - diff --git a/bringup/config/hexapod_robot.rviz b/bringup/config/hexapod_robot.rviz deleted file mode 100644 index f540827..0000000 --- a/bringup/config/hexapod_robot.rviz +++ /dev/null @@ -1,327 +0,0 @@ -Panels: - - Class: rviz_common/Displays - Help Height: 70 - Name: Displays - Property Tree Widget: - Expanded: - - /TF1 - Splitter Ratio: 0.5 - Tree Height: 438 - - Class: rviz_common/Views - Expanded: - - /Current View1 - Name: Views - Splitter Ratio: 0.5 -Visualization Manager: - Class: "" - Displays: - - Alpha: 0.5 - Cell Size: 1 - Class: rviz_default_plugins/Grid - Color: 160; 160; 164 - Enabled: true - Line Style: - Line Width: 0.029999999329447746 - Value: Lines - Name: Grid - Normal Cell Count: 0 - Offset: - X: 0 - Y: 0 - Z: 0 - Plane: XY - Plane Cell Count: 10 - Reference Frame: - Value: true - - Alpha: 0.800000011920929 - Class: rviz_default_plugins/RobotModel - Collision Enabled: false - Description File: "" - Description Source: Topic - Description Topic: - Depth: 5 - Durability Policy: Volatile - History Policy: Keep Last - Reliability Policy: Reliable - Value: /robot_description - Enabled: true - Links: - All Links Enabled: true - Expand Joint Details: false - Expand Link Details: false - Expand Tree: false - Link Tree Style: Links in Alphabetic Order - base_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - c1_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - c2_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - c3_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - c4_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - c5_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - c6_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - e1_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - e2_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - e3_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - e4_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - e5_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - e6_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - f1_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - f2_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - f3_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - f4_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - f5_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - f6_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - t1_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - t2_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - t3_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - t4_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - t5_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - t6_link: - Alpha: 1 - Show Axes: false - Show Trail: false - Value: true - Mass Properties: - Inertia: false - Mass: false - Name: RobotModel - TF Prefix: "" - Update Interval: 0 - Value: true - Visual Enabled: true - - Class: rviz_default_plugins/TF - Enabled: true - Frame Timeout: 15 - Frames: - All Enabled: true - base_link: - Value: true - c1_link: - Value: true - c2_link: - Value: true - c3_link: - Value: true - c4_link: - Value: true - c5_link: - Value: true - c6_link: - Value: true - e1_link: - Value: true - e2_link: - Value: true - e3_link: - Value: true - e4_link: - Value: true - e5_link: - Value: true - e6_link: - Value: true - f1_link: - Value: true - f2_link: - Value: true - f3_link: - Value: true - f4_link: - Value: true - f5_link: - Value: true - f6_link: - Value: true - t1_link: - Value: true - t2_link: - Value: true - t3_link: - Value: true - t4_link: - Value: true - t5_link: - Value: true - t6_link: - Value: true - Marker Scale: 0.30000001192092896 - Name: TF - Show Arrows: true - Show Axes: true - Show Names: false - Tree: - base_link: - c1_link: - f1_link: - t1_link: - e1_link: - {} - c2_link: - f2_link: - t2_link: - e2_link: - {} - c3_link: - f3_link: - t3_link: - e3_link: - {} - c4_link: - f4_link: - t4_link: - e4_link: - {} - c5_link: - f5_link: - t5_link: - e5_link: - {} - c6_link: - f6_link: - t6_link: - e6_link: - {} - Update Interval: 0 - Value: true - Enabled: true - Global Options: - Background Color: 48; 48; 48 - Fixed Frame: base_link - Frame Rate: 30 - Name: root - Tools: - - Class: rviz_default_plugins/MoveCamera - Transformation: - Current: - Class: rviz_default_plugins/TF - Value: true - Views: - Current: - Class: rviz_default_plugins/Orbit - Distance: 0.8691349625587463 - Enable Stereo Rendering: - Stereo Eye Separation: 0.05999999865889549 - Stereo Focal Distance: 1 - Swap Stereo Eyes: false - Value: false - Focal Point: - X: 0 - Y: 0 - Z: 0 - Focal Shape Fixed Size: true - Focal Shape Size: 0.05000000074505806 - Invert Z Axis: false - Name: Current View - Near Clip Distance: 0.009999999776482582 - Pitch: 0.559999942779541 - Target Frame: - Value: Orbit (rviz) - Yaw: 4.6249775886535645 - Saved: ~ -Window Geometry: - Displays: - collapsed: false - Height: 666 - Hide Left Dock: false - Hide Right Dock: false - QMainWindow State: 000000ff00000000fd0000000100000000000001560000023cfc0200000002fb000000100044006900730070006c006100790073010000003f0000023c000000cc00fffffffb0000000a0056006900650077007300000001d2000000a9000000a900ffffff000001ff0000023c00000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 - Views: - collapsed: false - Width: 859 - X: 0 - Y: 32 diff --git a/config/hexapod_robot.rviz b/config/hexapod_robot.rviz new file mode 100644 index 0000000..1ec916d --- /dev/null +++ b/config/hexapod_robot.rviz @@ -0,0 +1,669 @@ +Panels: + - Class: rviz_common/Displays + Help Height: 70 + Name: Displays + Property Tree Widget: + Expanded: + - /MotionPlanning1 + Splitter Ratio: 0.5 + Tree Height: 378 + - Class: rviz_common/Help + Name: Help + - Class: rviz_common/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz_default_plugins/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.029999999329447746 + Value: Lines + Name: Grid + Normal Cell Count: 0 + Offset: + X: 0 + Y: 0 + Z: 0 + Plane: XY + Plane Cell Count: 10 + Reference Frame: + Value: true + - Acceleration_Scaling_Factor: 0.1 + Class: moveit_rviz_plugin/MotionPlanning + Enabled: true + Move Group Namespace: "" + MoveIt_Allow_Approximate_IK: false + MoveIt_Allow_External_Program: false + MoveIt_Allow_Replanning: false + MoveIt_Allow_Sensor_Positioning: false + MoveIt_Planning_Attempts: 10 + MoveIt_Planning_Time: 5 + MoveIt_Use_Cartesian_Path: false + MoveIt_Use_Constraint_Aware_IK: false + MoveIt_Workspace: + Center: + X: 0 + Y: 0 + Z: 0 + Size: + X: 2 + Y: 2 + Z: 2 + Name: MotionPlanning + Planned Path: + Color Enabled: false + Interrupt Display: false + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + c1_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + c2_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + c3_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + c4_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + c5_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + c6_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + e1_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + e2_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + e3_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + e4_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + e5_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + e6_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + f1_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + f2_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + f3_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + f4_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + f5_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + f6_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + t1_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + t2_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + t3_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + t4_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + t5_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + t6_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Loop Animation: true + Robot Alpha: 0.5 + Robot Color: 150; 50; 150 + Show Robot Collision: false + Show Robot Visual: true + Show Trail: false + State Display Time: 0.05 s + Trail Step Size: 1 + Trajectory Topic: display_planned_path + Use Sim Time: false + Planning Metrics: + Payload: 1 + Show Joint Torques: false + Show Manipulability: false + Show Manipulability Index: false + Show Weight Limit: false + TextHeight: 0.07999999821186066 + Planning Request: + Colliding Link Color: 255; 0; 0 + Goal State Alpha: 1 + Goal State Color: 250; 128; 0 + Interactive Marker Size: 0.05000000074505806 + Joint Violation Color: 255; 0; 255 + Planning Group: e1_group + Query Goal State: true + Query Start State: false + Show Workspace: false + Start State Alpha: 1 + Start State Color: 0; 255; 0 + Planning Scene Topic: monitored_planning_scene + Robot Description: robot_description + Scene Geometry: + Scene Alpha: 1 + Scene Color: 50; 230; 50 + Scene Display Time: 0.009999999776482582 + Show Scene Geometry: true + Voxel Coloring: Z-Axis + Voxel Rendering: Occupied Voxels + Scene Robot: + Attached Body Color: 150; 50; 150 + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + c1_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + c2_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + c3_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + c4_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + c5_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + c6_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + e1_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + e2_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + e3_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + e4_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + e5_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + e6_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + f1_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + f2_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + f3_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + f4_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + f5_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + f6_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + t1_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + t2_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + t3_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + t4_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + t5_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + t6_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Robot Alpha: 0.5 + Show Robot Collision: false + Show Robot Visual: true + Value: true + Velocity_Scaling_Factor: 0.1 + - Class: moveit_rviz_plugin/Trajectory + Color Enabled: false + Enabled: true + Interrupt Display: false + Links: + All Links Enabled: true + Expand Joint Details: false + Expand Link Details: false + Expand Tree: false + Link Tree Style: Links in Alphabetic Order + base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + c1_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + c2_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + c3_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + c4_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + c5_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + c6_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + e1_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + e2_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + e3_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + e4_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + e5_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + e6_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + f1_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + f2_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + f3_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + f4_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + f5_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + f6_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + t1_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + t2_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + t3_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + t4_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + t5_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + t6_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Loop Animation: false + Name: Trajectory + Robot Alpha: 0.5 + Robot Color: 150; 50; 150 + Robot Description: robot_description + Show Robot Collision: false + Show Robot Visual: true + Show Trail: false + State Display Time: 3x + Trail Step Size: 1 + Trajectory Topic: /display_planned_path + Use Sim Time: false + Value: true + - Class: rviz_default_plugins/TF + Enabled: true + Frame Timeout: 15 + Frames: + All Enabled: true + base_link: + Value: true + c1_link: + Value: true + c2_link: + Value: true + c3_link: + Value: true + c4_link: + Value: true + c5_link: + Value: true + c6_link: + Value: true + e1_link: + Value: true + e2_link: + Value: true + e3_link: + Value: true + e4_link: + Value: true + e5_link: + Value: true + e6_link: + Value: true + f1_link: + Value: true + f2_link: + Value: true + f3_link: + Value: true + f4_link: + Value: true + f5_link: + Value: true + f6_link: + Value: true + t1_link: + Value: true + t2_link: + Value: true + t3_link: + Value: true + t4_link: + Value: true + t5_link: + Value: true + t6_link: + Value: true + Marker Scale: 0.10000000149011612 + Name: TF + Show Arrows: true + Show Axes: true + Show Names: false + Tree: + base_link: + c1_link: + f1_link: + t1_link: + e1_link: + {} + c2_link: + f2_link: + t2_link: + e2_link: + {} + c3_link: + f3_link: + t3_link: + e3_link: + {} + c4_link: + f4_link: + t4_link: + e4_link: + {} + c5_link: + f5_link: + t5_link: + e5_link: + {} + c6_link: + f6_link: + t6_link: + e6_link: + {} + Update Interval: 0 + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: base_link + Frame Rate: 30 + Name: root + Tools: + - Class: rviz_default_plugins/Interact + Hide Inactive Objects: true + - Class: rviz_default_plugins/MoveCamera + - Class: rviz_default_plugins/Select + Transformation: + Current: + Class: rviz_default_plugins/TF + Value: true + Views: + Current: + Class: rviz_default_plugins/Orbit + Distance: 0.6329568028450012 + Enable Stereo Rendering: + Stereo Eye Separation: 0.05999999865889549 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: -0.07758110761642456 + Y: 0.08254023641347885 + Z: 0.09184139221906662 + Focal Shape Fixed Size: true + Focal Shape Size: 0.05000000074505806 + Invert Z Axis: false + Name: Current View + Near Clip Distance: 0.009999999776482582 + Pitch: 0.5400001406669617 + Target Frame: base_link + Value: Orbit (rviz_default_plugins) + Yaw: 2.3151493072509766 + Saved: ~ +Window Geometry: + " - Trajectory Slider": + collapsed: false + Displays: + collapsed: false + Height: 1287 + Help: + collapsed: false + Hide Left Dock: false + Hide Right Dock: false + MotionPlanning: + collapsed: false + MotionPlanning - Trajectory Slider: + collapsed: false + QMainWindow State: 000000ff00000000fd0000000100000000000002b4000004a9fc0200000006fb00000044004d006f00740069006f006e0050006c0061006e006e0069006e00670020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000004400fffffffb000000100044006900730070006c006100790073010000003f00000200000000cc00fffffffb0000001c004d006f00740069006f006e0050006c0061006e006e0069006e00670100000245000001a10000019600fffffffb0000000800480065006c0070000000029a0000006e0000006f00fffffffb0000000a0056006900650077007301000003ec000000fc000000a900fffffffb000000280020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000004400ffffff0000063e000004a900000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Views: + collapsed: false + Width: 2296 + X: 0 + Y: 32 diff --git a/config/hexapod_robot.srdf b/config/hexapod_robot.srdf new file mode 100644 index 0000000..df01027 --- /dev/null +++ b/config/hexapod_robot.srdf @@ -0,0 +1,21 @@ + + + + + + + + + + + + + + + + + + + + + diff --git a/config/joint_limits.yaml b/config/joint_limits.yaml new file mode 100644 index 0000000..33387dc --- /dev/null +++ b/config/joint_limits.yaml @@ -0,0 +1,7 @@ +# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed + +# For beginners, we downscale velocity and acceleration limits. +# You can always specify higher scaling factors (<= 1.0) in your motion requests. # Increase the values below to 1.0 to always move at maximum speed. +default_velocity_scaling_factor: 0.1 +default_acceleration_scaling_factor: 0.1 + diff --git a/config/kinematics.yaml b/config/kinematics.yaml new file mode 100644 index 0000000..aa4f5c6 --- /dev/null +++ b/config/kinematics.yaml @@ -0,0 +1,77 @@ +e1_group: + kinematics_solver: pick_ik/PickIkPlugin + kinematics_solver_timeout: 0.05 + kinematics_solver_attempts: 3 + mode: global + position_scale: 1.0 + rotation_scale: 0.0 + position_threshold: 0.001 + orientation_threshold: 0.01 + cost_threshold: 0.001 + minimal_displacement_weight: 0.0 + gd_step_size: 0.0001 + +e2_group: + kinematics_solver: pick_ik/PickIkPlugin + kinematics_solver_timeout: 0.05 + kinematics_solver_attempts: 3 + mode: global + position_scale: 1.0 + rotation_scale: 0.0 + position_threshold: 0.001 + orientation_threshold: 0.01 + cost_threshold: 0.001 + minimal_displacement_weight: 0.0 + gd_step_size: 0.0001 + +e3_group: + kinematics_solver: pick_ik/PickIkPlugin + kinematics_solver_timeout: 0.05 + kinematics_solver_attempts: 3 + mode: global + position_scale: 1.0 + rotation_scale: 0.0 + position_threshold: 0.001 + orientation_threshold: 0.01 + cost_threshold: 0.001 + minimal_displacement_weight: 0.0 + gd_step_size: 0.0001 + +e4_group: + kinematics_solver: pick_ik/PickIkPlugin + kinematics_solver_timeout: 0.05 + kinematics_solver_attempts: 3 + mode: global + position_scale: 1.0 + rotation_scale: 0.0 + position_threshold: 0.001 + orientation_threshold: 0.01 + cost_threshold: 0.001 + minimal_displacement_weight: 0.0 + gd_step_size: 0.0001 + +e5_group: + kinematics_solver: pick_ik/PickIkPlugin + kinematics_solver_timeout: 0.05 + kinematics_solver_attempts: 3 + mode: global + position_scale: 1.0 + rotation_scale: 0.0 + position_threshold: 0.001 + orientation_threshold: 0.01 + cost_threshold: 0.001 + minimal_displacement_weight: 0.0 + gd_step_size: 0.0001 + +e6_group: + kinematics_solver: pick_ik/PickIkPlugin + kinematics_solver_timeout: 0.05 + kinematics_solver_attempts: 3 + mode: global + position_scale: 1.0 + rotation_scale: 0.0 + position_threshold: 0.001 + orientation_threshold: 0.01 + cost_threshold: 0.001 + minimal_displacement_weight: 0.0 + gd_step_size: 0.0001 diff --git a/config/moveit_controllers.yaml b/config/moveit_controllers.yaml new file mode 100644 index 0000000..1f4dfde --- /dev/null +++ b/config/moveit_controllers.yaml @@ -0,0 +1,81 @@ +# MoveIt uses this configuration for controller management + +moveit_controller_manager: moveit_simple_controller_manager/MoveItSimpleControllerManager + +moveit_simple_controller_manager: + controller_names: + - e1_group_controller + - e2_group_controller + - e3_group_controller + - e4_group_controller + - e5_group_controller + - e6_group_controller + + e1_group_controller: + type: FollowJointTrajectory + action_ns: follow_joint_trajectory + default: true + joints: + - c1_joint + - f1_joint + - t1_joint + action_ns: follow_joint_trajectory + default: true + + e2_group_controller: + type: FollowJointTrajectory + action_ns: follow_joint_trajectory + default: true + joints: + - c2_joint + - f2_joint + - t2_joint + action_ns: follow_joint_trajectory + default: true + + e3_group_controller: + type: FollowJointTrajectory + action_ns: follow_joint_trajectory + default: true + joints: + - c3_joint + - f3_joint + - t3_joint + action_ns: follow_joint_trajectory + default: true + + e4_group_controller: + type: FollowJointTrajectory + action_ns: follow_joint_trajectory + default: true + joints: + - c4_joint + - f4_joint + - t4_joint + action_ns: follow_joint_trajectory + default: true + + e5_group_controller: + type: FollowJointTrajectory + action_ns: follow_joint_trajectory + default: true + joints: + - c5_joint + - f5_joint + - t5_joint + action_ns: follow_joint_trajectory + default: true + + e6_group_controller: + type: FollowJointTrajectory + action_ns: follow_joint_trajectory + default: true + joints: + - c6_joint + - f6_joint + - t6_joint + action_ns: follow_joint_trajectory + default: true + + + \ No newline at end of file diff --git a/config/pilz_cartesian_limits.yaml b/config/pilz_cartesian_limits.yaml new file mode 100644 index 0000000..b2997ca --- /dev/null +++ b/config/pilz_cartesian_limits.yaml @@ -0,0 +1,6 @@ +# Limits for the Pilz planner +cartesian_limits: + max_trans_vel: 1.0 + max_trans_acc: 2.25 + max_trans_dec: -5.0 + max_rot_vel: 1.57 diff --git a/config/ros2_controllers.yaml b/config/ros2_controllers.yaml new file mode 100644 index 0000000..c0ae99d --- /dev/null +++ b/config/ros2_controllers.yaml @@ -0,0 +1,103 @@ +controller_manager: + ros__parameters: + update_rate: 50 + + joint_state_broadcaster: + type: joint_state_broadcaster/JointStateBroadcaster + + e1_group_controller: + type: joint_trajectory_controller/JointTrajectoryController + + e2_group_controller: + type: joint_trajectory_controller/JointTrajectoryController + + e3_group_controller: + type: joint_trajectory_controller/JointTrajectoryController + + e4_group_controller: + type: joint_trajectory_controller/JointTrajectoryController + + e5_group_controller: + type: joint_trajectory_controller/JointTrajectoryController + + e6_group_controller: + type: joint_trajectory_controller/JointTrajectoryController + + +e1_group_controller: + ros__parameters: + joints: + - c1_joint + - f1_joint + - t1_joint + + command_interfaces: + - position + + state_interfaces: + - position + +e2_group_controller: + ros__parameters: + joints: + - c2_joint + - f2_joint + - t2_joint + + command_interfaces: + - position + + state_interfaces: + - position + +e3_group_controller: + ros__parameters: + joints: + - c3_joint + - f3_joint + - t3_joint + + command_interfaces: + - position + + state_interfaces: + - position + +e4_group_controller: + ros__parameters: + joints: + - c4_joint + - f4_joint + - t4_joint + + command_interfaces: + - position + + state_interfaces: + - position + +e5_group_controller: + ros__parameters: + joints: + - c5_joint + - f5_joint + - t5_joint + + command_interfaces: + - position + + state_interfaces: + - position + +e6_group_controller: + ros__parameters: + joints: + - c6_joint + - f6_joint + - t6_joint + + command_interfaces: + - position + + state_interfaces: + - position diff --git a/description/urdf/hexapod_robot.urdf.xacro b/config/urdf/hexapod_robot.urdf.xacro similarity index 78% rename from description/urdf/hexapod_robot.urdf.xacro rename to config/urdf/hexapod_robot.urdf.xacro index 69d991d..532aab9 100644 --- a/description/urdf/hexapod_robot.urdf.xacro +++ b/config/urdf/hexapod_robot.urdf.xacro @@ -1,7 +1,7 @@ - - + + @@ -23,6 +23,6 @@ - + diff --git a/description/urdf/hexapod_robot_macros.xacro b/config/urdf/hexapod_robot_macros.xacro similarity index 96% rename from description/urdf/hexapod_robot_macros.xacro rename to config/urdf/hexapod_robot_macros.xacro index 59b15a9..802a899 100644 --- a/description/urdf/hexapod_robot_macros.xacro +++ b/config/urdf/hexapod_robot_macros.xacro @@ -60,7 +60,7 @@ - + @@ -91,7 +91,7 @@ - + @@ -149,7 +149,7 @@ - + diff --git a/description/urdf/hexapod_robot_materials.xacro b/config/urdf/hexapod_robot_materials.xacro similarity index 100% rename from description/urdf/hexapod_robot_materials.xacro rename to config/urdf/hexapod_robot_materials.xacro diff --git a/description/urdf/hexapod_robot_ros2_control.xacro b/config/urdf/hexapod_robot_ros2_control.xacro similarity index 94% rename from description/urdf/hexapod_robot_ros2_control.xacro rename to config/urdf/hexapod_robot_ros2_control.xacro index 7b48214..a42407a 100644 --- a/description/urdf/hexapod_robot_ros2_control.xacro +++ b/config/urdf/hexapod_robot_ros2_control.xacro @@ -5,23 +5,23 @@ - -1 - 1 + -1.57 + 1.57 - -1 - 1 + -1.57 + 1.57 - -1 - 1 + -1.57 + 1.57 diff --git a/kinematics/hexapod_robot_ik_service.cpp b/kinematics/hexapod_robot_ik_service.cpp index 066f590..3dcd089 100644 --- a/kinematics/hexapod_robot_ik_service.cpp +++ b/kinematics/hexapod_robot_ik_service.cpp @@ -6,8 +6,8 @@ void ik(const std::shared_ptr request, std::shared_ptr response) { - response -> bar = request -> foo; - + response -> angles.push_back(42); + } int main(int argc, char **argv) { diff --git a/bringup/launch/hexapod_robot.launch.py b/launch/hexapod_robot.launch.py similarity index 88% rename from bringup/launch/hexapod_robot.launch.py rename to launch/hexapod_robot.launch.py index 24dd10e..e416425 100644 --- a/bringup/launch/hexapod_robot.launch.py +++ b/launch/hexapod_robot.launch.py @@ -7,6 +7,9 @@ from launch.event_handlers import OnProcessExit from launch_ros.actions import Node from launch_ros.substitutions import FindPackageShare +from moveit_configs_utils import MoveItConfigsBuilder + + def generate_launch_description(): robot_description_content = Command([ @@ -15,7 +18,7 @@ def generate_launch_description(): PathJoinSubstitution( [ FindPackageShare("hexapod_robot"), - "description", + "config", "urdf", "hexapod_robot.urdf.xacro" ] @@ -24,7 +27,7 @@ def generate_launch_description(): ) robot_description = {"robot_description": robot_description_content} - robot_controllers = PathJoinSubstitution([FindPackageShare("hexapod_robot"), "config", "controllers.yaml"]) + ros2_controllers = PathJoinSubstitution([FindPackageShare("hexapod_robot"), "config", "ros2_controllers.yaml"]) robot_state_publisher_node = Node( package = "robot_state_publisher", @@ -33,10 +36,10 @@ def generate_launch_description(): output = "both" ) - control_node = Node( + ros2_control_node = Node( package = "controller_manager", executable = "ros2_control_node", - parameters = [robot_description, robot_controllers], + parameters = [robot_description, ros2_controllers], output="both" ) @@ -63,7 +66,7 @@ def generate_launch_description(): joint_trajectory_controller_spawner = Node( package = "controller_manager", executable = "spawner", - arguments = ["joint_trajectory_controller", "--controller-manager", "/controller_manager"] + arguments = ["e1_group_controller", "--controller-manager", "/controller_manager"] ) @@ -90,7 +93,7 @@ def generate_launch_description(): nodes = [ - control_node, + ros2_control_node, robot_state_publisher_node, joint_state_broadcaster_spawner, #delay_rviz_after_joint_state_broadcaster_spawner, diff --git a/bringup/launch/hexapod_robot_gui.launch.py b/launch/hexapod_robot_gui.launch.py similarity index 61% rename from bringup/launch/hexapod_robot_gui.launch.py rename to launch/hexapod_robot_gui.launch.py index c63d7ef..7bd9990 100644 --- a/bringup/launch/hexapod_robot_gui.launch.py +++ b/launch/hexapod_robot_gui.launch.py @@ -3,40 +3,44 @@ from launch.actions import RegisterEventHandler from launch.substitutions import Command, FindExecutable, LaunchConfiguration, PathJoinSubstitution from launch.event_handlers import OnProcessExit - from launch_ros.actions import Node from launch_ros.substitutions import FindPackageShare +from moveit_configs_utils import MoveItConfigsBuilder + + def generate_launch_description(): - robot_description_content = Command([ - PathJoinSubstitution([FindExecutable(name="xacro")]), - " ", - PathJoinSubstitution( - [ - FindPackageShare("hexapod_robot"), - "description", - "urdf", - "hexapod_robot.urdf.xacro" - ] - ) - ] + moveit_config = ( + MoveItConfigsBuilder("hexapod_robot", package_name = "hexapod_robot") + + .planning_scene_monitor( + publish_robot_description=True, publish_robot_description_semantic=True + ) + .planning_pipelines(pipelines = ["ompl"]) + .to_moveit_configs() ) - robot_description = {"robot_description": robot_description_content} - robot_controllers = PathJoinSubstitution([FindPackageShare("hexapod_robot"), "config", "controllers.yaml"]) + move_group_node = Node( + package = "moveit_ros_move_group", + executable = "move_group", + output = "screen", + parameters = [moveit_config.to_dict()] + ) + + ros2_controllers = PathJoinSubstitution([FindPackageShare("hexapod_robot"), "config", "ros2_controllers.yaml"]) robot_state_publisher_node = Node( package = "robot_state_publisher", executable = "robot_state_publisher", - parameters = [robot_description], + parameters = [moveit_config.robot_description], output = "both" ) - control_node = Node( + ros2_control_node = Node( package = "controller_manager", executable = "ros2_control_node", - parameters = [robot_description, robot_controllers], + parameters = [moveit_config.robot_description, ros2_controllers], output="both" ) @@ -46,6 +50,7 @@ def generate_launch_description(): arguments = ['-d', PathJoinSubstitution([FindPackageShare("hexapod_robot"), "config", "hexapod_robot.rviz"])], name = "rviz2", output = "screen", + parameters = [moveit_config.planning_pipelines, moveit_config.robot_description_kinematics] ) joint_state_broadcaster_spawner = Node ( @@ -53,17 +58,11 @@ def generate_launch_description(): executable = "spawner", arguments = ["joint_state_broadcaster", "--controller-manager", "/controller_manager"] ) - - # forward_position_controller_spawner = Node( - # package = "controller_manager", - # executable = "spawner", - # arguments = ["forward_position_controller", "--controller-manager", "/controller_manager"] - # ) joint_trajectory_controller_spawner = Node( package = "controller_manager", executable = "spawner", - arguments = ["joint_trajectory_controller", "--controller-manager", "/controller_manager"] + arguments = ["e1_group_controller", "e2_group_controller", "e3_group_controller", "e4_group_controller", "e5_group_controller", "e6_group_controller", "--controller-manager", "/controller_manager"] ) @@ -73,13 +72,7 @@ def generate_launch_description(): on_exit = [rviz_node] ) ) - - # delay_forward_position_controller_spawner_after_joint_state_broadcaster_spawner = RegisterEventHandler( - # event_handler = OnProcessExit( - # target_action = joint_state_broadcaster_spawner, - # on_exit = [forward_position_controller_spawner] - # ) - # ) + delay_joint_trajectory_controller_spawner_after_joint_state_broadcaster_spawner = RegisterEventHandler( event_handler = OnProcessExit( @@ -90,8 +83,9 @@ def generate_launch_description(): nodes = [ - control_node, robot_state_publisher_node, + move_group_node, + ros2_control_node, joint_state_broadcaster_spawner, delay_rviz_after_joint_state_broadcaster_spawner, # delay_forward_position_controller_spawner_after_joint_state_broadcaster_spawner, diff --git a/package.xml b/package.xml index d90d97a..b627a3e 100644 --- a/package.xml +++ b/package.xml @@ -9,7 +9,11 @@ ament_cmake rosidl_default_generators + + geometry_msgs + rosidl_default_runtime + geometry_msgs rosidl_interface_packages diff --git a/srv/HexapodRobotInverseKinematics.srv b/srv/HexapodRobotInverseKinematics.srv index 9ce93a1..dbc5c5f 100644 --- a/srv/HexapodRobotInverseKinematics.srv +++ b/srv/HexapodRobotInverseKinematics.srv @@ -1,3 +1,4 @@ -int64 foo +geometry_msgs/Pose body +geometry_msgs/Vector3[] leg_tips --- -int64 bar +float64[] angles