Skip to content
Merged
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
431 changes: 431 additions & 0 deletions setup/draw_hitboxes.py

Large diffs are not rendered by default.

23 changes: 23 additions & 0 deletions src/Arm/arm_control/.setup_assistant
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
moveit_setup_assistant_config:
urdf:
package: rover_urdf
relative_path: urdf/rover_urdf.urdf.xacro
srdf:
relative_path: config/rover_urdf.srdf
package_settings:
author_name: Connor Needham
author_email: connor.needham2015@gmail.com
generated_timestamp: 1767296302
control_xacro:
command:
[]
state:
[]
modified_urdf:
xacros:
- control_xacro
control_xacro:
command:
[]
state:
[]
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
cmake_minimum_required(VERSION 3.22)
project(arm_srdf)
project(arm_control)

find_package(ament_cmake REQUIRED)

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -26,8 +26,8 @@ scale:
command_out_type: trajectory_msgs/JointTrajectory

# What to publish? Can save some bandwidth as most robots only require positions or velocities
publish_joint_positions: false
publish_joint_velocities: true
publish_joint_positions: true
publish_joint_velocities: false
publish_joint_accelerations: false

#low_pass_filter_coeff: 2.0
Expand All @@ -43,9 +43,9 @@ is_primary_planning_scene_monitor: false
check_octomap_collisions: false # Check collision against the octomap (if a 3D sensor plugin is available)

## MoveIt properties
move_group_name: rover_arm # Often 'manipulator' or 'arm'
move_group_name: arm # Often 'manipulator' or 'arm'
planning_frame: Link_1
ee_frame_name: eef_link
ee_frame_name: EndEffector
robot_link_command_frame: Link_1

## Stopping behaviour
Expand All @@ -70,10 +70,10 @@ cartesian_command_in_topic: ~/delta_twist_cmds # Topic for incoming Cartesian t
joint_command_in_topic: ~/delta_joint_cmds # Topic for incoming joint angle commands
joint_topic: /joint_states # Get joint states from this tpoic
status_topic: ~/status # Publish status to this topic
command_out_topic: /rover_arm_controller/joint_trajectory # Publish outgoing commands here
command_out_topic: /arm_controller/joint_trajectory # Publish outgoing commands here

## Collision checking for the entire robot body
check_collisions: false # Check collisions?
check_collisions: true # Check collisions?
collision_check_rate: 10.0 # [Hz] Collision-checking can easily bog down a CPU if done too often.
self_collision_proximity_threshold: 0.01 # Start decelerating when a self-collision is this far [m]
scene_collision_proximity_threshold: 0.02 # Start decelerating when a scene collision is this far [m]
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
rover_arm:
arm:
kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin
kinematics_solver_search_resolution: 0.0050000000000000001
kinematics_solver_timeout: 0.0050000000000000001
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ Visualization Manager:
Robot Alpha: 0.5
Value: true
Global Options:
Fixed Frame: Link_1
Fixed Frame: base_link
Tools:
- Class: rviz_default_plugins/Interact
- Class: rviz_default_plugins/MoveCamera
Expand All @@ -43,7 +43,7 @@ Visualization Manager:
Z: 0.30
Name: Current View
Pitch: 0.5
Target Frame: Link_1
Target Frame: base_link
Yaw: -0.623
Window Geometry:
Height: 975
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,9 +4,9 @@ moveit_controller_manager: moveit_simple_controller_manager/MoveItSimpleControll

moveit_simple_controller_manager:
controller_names:
- rover_arm_controller
- arm_controller

rover_arm_controller:
arm_controller:
type: FollowJointTrajectory
joints:
- Joint_1
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,14 +3,14 @@ controller_manager:
ros__parameters:
update_rate: 100 # Hz

rover_arm_controller:
arm_controller:
type: joint_trajectory_controller/JointTrajectoryController


joint_state_broadcaster:
type: joint_state_broadcaster/JointStateBroadcaster

rover_arm_controller:
arm_controller:
ros__parameters:
joints:
- Joint_1
Expand All @@ -20,9 +20,7 @@ rover_arm_controller:
- Joint_5
- Joint_6
command_interfaces:
- velocity
- position
state_interfaces:
- position
- velocity
allow_integration_in_goal_trajectories: true
open_loop_control: true
- velocity
292 changes: 292 additions & 0 deletions src/Arm/arm_control/config/rover_urdf.srdf

Large diffs are not rendered by default.

9 changes: 9 additions & 0 deletions src/Arm/arm_control/launch/move_group.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
from moveit_configs_utils import MoveItConfigsBuilder
from moveit_configs_utils.launches import generate_move_group_launch


def generate_launch_description():
moveit_config = MoveItConfigsBuilder(
"rover_urdf", package_name="arm_control"
).to_moveit_configs()
return generate_move_group_launch(moveit_config)
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,6 @@

def generate_launch_description():
moveit_config = MoveItConfigsBuilder(
"arm_urdf", package_name="arm_srdf"
"rover_urdf", package_name="arm_control"
).to_moveit_configs()
return generate_moveit_rviz_launch(moveit_config)
Original file line number Diff line number Diff line change
Expand Up @@ -40,26 +40,16 @@ def arm_launch(moveit_config, launch_package_path=None) -> LaunchDescription:
Launch a self-contained MoveIt demo.

Includes:
* robot_state_publisher
* move_group
* moveit_rviz
* moveit_rviz (Optional)
* ros2_control_node + controller spawners
"""
if launch_package_path is None:
launch_package_path = moveit_config.package_path

ld = LaunchDescription()

# Launch arguments
ld.add_action(DeclareBooleanLaunchArg("use_composition", default_value=True))
ld.add_action(
DeclareBooleanLaunchArg("use_intra_process_comms", default_value=True)
)
ld.add_action(DeclareBooleanLaunchArg("use_rviz", default_value=False))

use_composition = LaunchConfiguration("use_composition")
use_intra_process_comms = LaunchConfiguration("use_intra_process_comms")

# Move group
ld.add_action(generate_move_group_launch(moveit_config))

Expand All @@ -75,11 +65,10 @@ def arm_launch(moveit_config, launch_package_path=None) -> LaunchDescription:
)

# Common parameters
servo_yaml = load_yaml("arm_srdf", "config/arm_config.yaml")
servo_yaml = load_yaml("arm_control", "config/arm_config.yaml")
parameters = [
{
"moveit_servo": servo_yaml,
"use_intra_process_comms": use_intra_process_comms,
"publish_frequency": 15.0,
},
moveit_config.robot_description,
Expand All @@ -95,69 +84,29 @@ def arm_launch(moveit_config, launch_package_path=None) -> LaunchDescription:
parameters=parameters,
remappings=[("/controller_manager/robot_description", "/robot_description")],
)

# Non-composed nodes
load_nodes = GroupAction(
condition=IfCondition(PythonExpression(["not ", use_composition])),
actions=[
Node(
package="moveit_servo",
executable="servo_node_main",
parameters=parameters,
output="screen",
),
Node(
package="robot_state_publisher",
executable="robot_state_publisher",
name="robot_state_publisher",
parameters=parameters,
),
],
)

# Composable container
container_name = "arm_container"
container = ComposableNodeContainer(
namespace="",
package="rclcpp_components",
executable="component_container_isolated",
name=container_name,
servo_node = Node(
package="moveit_servo",
executable="servo_node_main",
parameters=parameters,
output="screen",
condition=IfCondition(use_composition),
)

# Composable nodes (loaded into container when composition is enabled)
load_composable_nodes = LoadComposableNodes(
condition=IfCondition(use_composition),
target_container=container_name,
composable_node_descriptions=[
ComposableNode(
package="moveit_servo",
plugin="moveit_servo::ServoNode",
name="servo_node",
parameters=parameters,
),
ComposableNode(
package="robot_state_publisher",
plugin="robot_state_publisher::RobotStatePublisher",
name="robot_state_publisher",
parameters=parameters,
),
],
)

# Add actions to launch description
ld.add_action(control_node)
ld.add_action(load_nodes)
ld.add_action(container)
ld.add_action(load_composable_nodes)
ld.add_action(servo_node)
return ld


def generate_launch_description() -> LaunchDescription:
urdf_pkg = get_package_share_directory("rover_urdf")
urdf_path = os.path.join(
urdf_pkg,
"urdf",
"rover_urdf.urdf.xacro",
)
moveit_config = (
MoveItConfigsBuilder("arm_urdf", package_name="arm_srdf")
.robot_description(file_path="config/arm_urdf.urdf.xacro")
MoveItConfigsBuilder("rover_urdf", package_name="arm_control")
.robot_description(file_path=urdf_path)
.to_moveit_configs()
)
return arm_launch(moveit_config)
9 changes: 9 additions & 0 deletions src/Arm/arm_control/launch/spawn_controllers.launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
from moveit_configs_utils import MoveItConfigsBuilder
from moveit_configs_utils.launches import generate_spawn_controllers_launch


def generate_launch_description():
moveit_config = MoveItConfigsBuilder(
"rover_urdf", package_name="arm_control"
).to_moveit_configs()
return generate_spawn_controllers_launch(moveit_config)
18 changes: 6 additions & 12 deletions src/Arm/arm_srdf/package.xml → src/Arm/arm_control/package.xml
Original file line number Diff line number Diff line change
@@ -1,20 +1,20 @@
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>arm_srdf</name>
<name>arm_control</name>
<version>0.3.0</version>
<description>
An automatically generated package with all the configuration and launch files for using the arm_urdf with the MoveIt Motion Planning Framework
An automatically generated package with all the configuration and launch files for using the rover_urdf with the MoveIt Motion Planning Framework
</description>
<maintainer email="wyf132@gmail.com">William Fan</maintainer>
<maintainer email="connor.needham2015@gmail.com">Connor Needham</maintainer>

<license>BSD</license>

<url type="website">http://moveit.ros.org/</url>
<url type="bugtracker">https://github.com/ros-planning/moveit2/issues</url>
<url type="repository">https://github.com/ros-planning/moveit2</url>

<author email="wyf132@gmail.com">William Fan</author>
<author email="connor.needham2015@gmail.com">Connor Needham</author>

<buildtool_depend>ament_cmake</buildtool_depend>

Expand All @@ -30,21 +30,15 @@
We don't include them by default to prevent installing gazebo and all its dependencies. -->
<!-- <exec_depend>joint_trajectory_controller</exec_depend> -->
<!-- <exec_depend>gazebo_ros_control</exec_depend> -->
<exec_depend>arm_urdf</exec_depend>
<exec_depend>controller_manager</exec_depend>
<exec_depend>moveit_configs_utils</exec_depend>
<exec_depend>moveit_ros_move_group</exec_depend>
<exec_depend>moveit_ros_visualization</exec_depend>
<exec_depend>moveit_ros_warehouse</exec_depend>
<exec_depend>moveit_servo</exec_depend>
<exec_depend>moveit_setup_assistant</exec_depend>
<exec_depend>robot_state_publisher</exec_depend>
<exec_depend>rover_urdf</exec_depend>
<exec_depend>rviz2</exec_depend>
<exec_depend>rviz_common</exec_depend>
<exec_depend>rviz_default_plugins</exec_depend>
<exec_depend>tf2_ros</exec_depend>
<exec_depend>warehouse_ros</exec_depend>
<exec_depend>ros_phoenix</exec_depend>
<exec_depend>xacro</exec_depend>


<export>
Expand Down
27 changes: 0 additions & 27 deletions src/Arm/arm_srdf/.setup_assistant

This file was deleted.

33 changes: 0 additions & 33 deletions src/Arm/arm_srdf/config/arm_urdf.srdf

This file was deleted.

Loading