diff --git a/.setup_assistant b/.setup_assistant
new file mode 100644
index 0000000..7aa4302
--- /dev/null
+++ b/.setup_assistant
@@ -0,0 +1,11 @@
+moveit_setup_assistant_config:
+ URDF:
+ package: uvicarm2024
+ relative_path: urdf/uvicarm2024.urdf
+ xacro_args: ""
+ SRDF:
+ relative_path: config/ASY, ROBOTIC ARM 2024, URDF.srdf
+ CONFIG:
+ author_name: joshua blanch
+ author_email: joshuamblanch@gmail.com
+ generated_timestamp: 1723591896
\ No newline at end of file
diff --git a/CMakeLists.txt b/CMakeLists.txt
new file mode 100644
index 0000000..cb55523
--- /dev/null
+++ b/CMakeLists.txt
@@ -0,0 +1,10 @@
+cmake_minimum_required(VERSION 3.1.3)
+project(moveitarm)
+
+find_package(catkin REQUIRED)
+
+catkin_package()
+
+install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
+ PATTERN "setup_assistant.launch" EXCLUDE)
+install(DIRECTORY config DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
diff --git a/config/ASY, ROBOTIC ARM 2024, URDF.srdf b/config/ASY, ROBOTIC ARM 2024, URDF.srdf
new file mode 100644
index 0000000..69f33ad
--- /dev/null
+++ b/config/ASY, ROBOTIC ARM 2024, URDF.srdf
@@ -0,0 +1,37 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/config/cartesian_limits.yaml b/config/cartesian_limits.yaml
new file mode 100644
index 0000000..7df72f6
--- /dev/null
+++ b/config/cartesian_limits.yaml
@@ -0,0 +1,5 @@
+cartesian_limits:
+ max_trans_vel: 1
+ max_trans_acc: 2.25
+ max_trans_dec: -5
+ max_rot_vel: 1.57
diff --git a/config/chomp_planning.yaml b/config/chomp_planning.yaml
new file mode 100644
index 0000000..eb9c912
--- /dev/null
+++ b/config/chomp_planning.yaml
@@ -0,0 +1,18 @@
+planning_time_limit: 10.0
+max_iterations: 200
+max_iterations_after_collision_free: 5
+smoothness_cost_weight: 0.1
+obstacle_cost_weight: 1.0
+learning_rate: 0.01
+smoothness_cost_velocity: 0.0
+smoothness_cost_acceleration: 1.0
+smoothness_cost_jerk: 0.0
+ridge_factor: 0.0
+use_pseudo_inverse: false
+pseudo_inverse_ridge_factor: 1e-4
+joint_update_limit: 0.1
+collision_clearance: 0.2
+collision_threshold: 0.07
+use_stochastic_descent: true
+enable_failure_recovery: false
+max_recovery_attempts: 5
diff --git a/config/fake_controllers.yaml b/config/fake_controllers.yaml
new file mode 100644
index 0000000..0bb2077
--- /dev/null
+++ b/config/fake_controllers.yaml
@@ -0,0 +1,19 @@
+controller_list:
+ - name: fake_summit_controller
+ type: $(arg fake_execution_type)
+ joints:
+ - joint0
+ - joint1
+ - joint2
+ - joint3
+ - joint4
+ - end_effector_joint
+ - name: fake_hand_controller
+ type: $(arg fake_execution_type)
+ joints:
+ - end_effector_joint
+initial: # Define initial robot poses per group
+# - group: summit
+# pose: home
+
+ []
\ No newline at end of file
diff --git a/config/gazebo_controllers.yaml b/config/gazebo_controllers.yaml
new file mode 100644
index 0000000..e4d2eb0
--- /dev/null
+++ b/config/gazebo_controllers.yaml
@@ -0,0 +1,4 @@
+# Publish joint_states
+joint_state_controller:
+ type: joint_state_controller/JointStateController
+ publish_rate: 50
diff --git a/config/joint_limits.yaml b/config/joint_limits.yaml
new file mode 100644
index 0000000..0464d10
--- /dev/null
+++ b/config/joint_limits.yaml
@@ -0,0 +1,40 @@
+# 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
+
+# Specific joint properties can be changed with the keys [max_position, min_position, max_velocity, max_acceleration]
+# Joint limits can be turned off with [has_velocity_limits, has_acceleration_limits]
+joint_limits:
+ end_effector_joint:
+ has_velocity_limits: true
+ max_velocity: 1
+ has_acceleration_limits: false
+ max_acceleration: 0
+ joint0:
+ has_velocity_limits: true
+ max_velocity: 1
+ has_acceleration_limits: false
+ max_acceleration: 0
+ joint1:
+ has_velocity_limits: true
+ max_velocity: 1
+ has_acceleration_limits: false
+ max_acceleration: 0
+ joint2:
+ has_velocity_limits: true
+ max_velocity: 1
+ has_acceleration_limits: false
+ max_acceleration: 0
+ joint3:
+ has_velocity_limits: true
+ max_velocity: 1
+ has_acceleration_limits: false
+ max_acceleration: 0
+ joint4:
+ has_velocity_limits: true
+ max_velocity: 1
+ has_acceleration_limits: false
+ max_acceleration: 0
\ No newline at end of file
diff --git a/config/kinematics.yaml b/config/kinematics.yaml
new file mode 100644
index 0000000..07cf027
--- /dev/null
+++ b/config/kinematics.yaml
@@ -0,0 +1,8 @@
+summit:
+ kinematics_solver: trac_ik_kinematics_plugin/TRAC_IKKinematicsPlugin
+ kinematics_solver_search_resolution: 0.005
+ kinematics_solver_timeout: 0.005
+ goal_joint_tolerance: 0.0001
+ goal_position_tolerance: 0.0001
+ goal_orientation_tolerance: 0.001
+ solve_type: Distance
\ No newline at end of file
diff --git a/config/ompl_planning.yaml b/config/ompl_planning.yaml
new file mode 100644
index 0000000..fac805d
--- /dev/null
+++ b/config/ompl_planning.yaml
@@ -0,0 +1,226 @@
+planner_configs:
+ AnytimePathShortening:
+ type: geometric::AnytimePathShortening
+ shortcut: true # Attempt to shortcut all new solution paths
+ hybridize: true # Compute hybrid solution trajectories
+ max_hybrid_paths: 24 # Number of hybrid paths generated per iteration
+ num_planners: 4 # The number of default planners to use for planning
+ planners: "" # A comma-separated list of planner types (e.g., "PRM,EST,RRTConnect"Optionally, planner parameters can be passed to change the default:"PRM[max_nearest_neighbors=5],EST[goal_bias=.5],RRT[range=10. goal_bias=.1]"
+ SBL:
+ type: geometric::SBL
+ range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
+ EST:
+ type: geometric::EST
+ range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0 setup()
+ goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05
+ LBKPIECE:
+ type: geometric::LBKPIECE
+ range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
+ border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9
+ min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5
+ BKPIECE:
+ type: geometric::BKPIECE
+ range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
+ border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9
+ failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5
+ min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5
+ KPIECE:
+ type: geometric::KPIECE
+ range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
+ goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05
+ border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 (0.0,1.]
+ failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5
+ min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5
+ RRT:
+ type: geometric::RRT
+ range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
+ goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05
+ RRTConnect:
+ type: geometric::RRTConnect
+ range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
+ RRTstar:
+ type: geometric::RRTstar
+ range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
+ goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05
+ delay_collision_checking: 1 # Stop collision checking as soon as C-free parent found. default 1
+ TRRT:
+ type: geometric::TRRT
+ range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
+ goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05
+ max_states_failed: 10 # when to start increasing temp. default: 10
+ temp_change_factor: 2.0 # how much to increase or decrease temp. default: 2.0
+ min_temperature: 10e-10 # lower limit of temp change. default: 10e-10
+ init_temperature: 10e-6 # initial temperature. default: 10e-6
+ frontier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup()
+ frontier_node_ratio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1
+ k_constant: 0.0 # value used to normalize expresssion. default: 0.0 set in setup()
+ PRM:
+ type: geometric::PRM
+ max_nearest_neighbors: 10 # use k nearest neighbors. default: 10
+ PRMstar:
+ type: geometric::PRMstar
+ FMT:
+ type: geometric::FMT
+ num_samples: 1000 # number of states that the planner should sample. default: 1000
+ radius_multiplier: 1.1 # multiplier used for the nearest neighbors search radius. default: 1.1
+ nearest_k: 1 # use Knearest strategy. default: 1
+ cache_cc: 1 # use collision checking cache. default: 1
+ heuristics: 0 # activate cost to go heuristics. default: 0
+ extended_fmt: 1 # activate the extended FMT*: adding new samples if planner does not finish successfully. default: 1
+ BFMT:
+ type: geometric::BFMT
+ num_samples: 1000 # number of states that the planner should sample. default: 1000
+ radius_multiplier: 1.0 # multiplier used for the nearest neighbors search radius. default: 1.0
+ nearest_k: 1 # use the Knearest strategy. default: 1
+ balanced: 0 # exploration strategy: balanced true expands one tree every iteration. False will select the tree with lowest maximum cost to go. default: 1
+ optimality: 1 # termination strategy: optimality true finishes when the best possible path is found. Otherwise, the algorithm will finish when the first feasible path is found. default: 1
+ heuristics: 1 # activates cost to go heuristics. default: 1
+ cache_cc: 1 # use the collision checking cache. default: 1
+ extended_fmt: 1 # Activates the extended FMT*: adding new samples if planner does not finish successfully. default: 1
+ PDST:
+ type: geometric::PDST
+ STRIDE:
+ type: geometric::STRIDE
+ range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
+ goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05
+ use_projected_distance: 0 # whether nearest neighbors are computed based on distances in a projection of the state rather distances in the state space itself. default: 0
+ degree: 16 # desired degree of a node in the Geometric Near-neightbor Access Tree (GNAT). default: 16
+ max_degree: 18 # max degree of a node in the GNAT. default: 12
+ min_degree: 12 # min degree of a node in the GNAT. default: 12
+ max_pts_per_leaf: 6 # max points per leaf in the GNAT. default: 6
+ estimated_dimension: 0.0 # estimated dimension of the free space. default: 0.0
+ min_valid_path_fraction: 0.2 # Accept partially valid moves above fraction. default: 0.2
+ BiTRRT:
+ type: geometric::BiTRRT
+ range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
+ temp_change_factor: 0.1 # how much to increase or decrease temp. default: 0.1
+ init_temperature: 100 # initial temperature. default: 100
+ frontier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup()
+ frontier_node_ratio: 0.1 # 1/10, or 1 nonfrontier for every 10 frontier. default: 0.1
+ cost_threshold: 1e300 # the cost threshold. Any motion cost that is not better will not be expanded. default: inf
+ LBTRRT:
+ type: geometric::LBTRRT
+ range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
+ goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05
+ epsilon: 0.4 # optimality approximation factor. default: 0.4
+ BiEST:
+ type: geometric::BiEST
+ range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
+ ProjEST:
+ type: geometric::ProjEST
+ range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
+ goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05
+ LazyPRM:
+ type: geometric::LazyPRM
+ range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
+ LazyPRMstar:
+ type: geometric::LazyPRMstar
+ SPARS:
+ type: geometric::SPARS
+ stretch_factor: 3.0 # roadmap spanner stretch factor. multiplicative upper bound on path quality. It does not make sense to make this parameter more than 3. default: 3.0
+ sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25
+ dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001
+ max_failures: 1000 # maximum consecutive failure limit. default: 1000
+ SPARStwo:
+ type: geometric::SPARStwo
+ stretch_factor: 3.0 # roadmap spanner stretch factor. multiplicative upper bound on path quality. It does not make sense to make this parameter more than 3. default: 3.0
+ sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25
+ dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001
+ max_failures: 5000 # maximum consecutive failure limit. default: 5000
+ AITstar:
+ type: geometric::AITstar
+ use_k_nearest: 1 # whether to use a k-nearest RGG connection model (1) or an r-disc model (0). Default: 1
+ rewire_factor: 1.001 # rewire factor of the RGG. Valid values: [1.0:0.01:3.0]. Default: 1.001
+ samples_per_batch: 100 # batch size. Valid values: [1:1:1000]. Default: 100
+ use_graph_pruning: 1 # enable graph pruning (1) or not (0). Default: 1
+ find_approximate_solutions: 0 # track approximate solutions (1) or not (0). Default: 0
+ set_max_num_goals: 1 # maximum number of goals sampled from sampleable goal regions. Valid values: [1:1:1000]. Default: 1
+ ABITstar:
+ type: geometric::ABITstar
+ use_k_nearest: 1 # whether to use a k-nearest RGG connection model (1) or an r-disc model (0). Default: 1
+ rewire_factor: 1.001 # rewire factor of the RGG. Valid values: [1.0:0.01:3.0]. Default: 1.001
+ samples_per_batch: 100 # batch size. Valid values: [1:1:1000]. Default: 100
+ use_graph_pruning: 1 # enable graph pruning (1) or not (0). Default: 1
+ prune_threshold_as_fractional_cost_change: 0.1 # fractional change in the solution cost AND problem measure necessary for pruning to occur. Default: 0.1
+ delay_rewiring_to_first_solution: 0 # delay (1) or not (0) rewiring until a solution is found. Default: 0
+ use_just_in_time_sampling: 0 # delay the generation of samples until they are * necessary. Only works with r-disc connection and path length minimization. Default: 0
+ drop_unconnected_samples_on_prune: 0 # drop unconnected samples when pruning, regardless of their heuristic value. Default: 0
+ stop_on_each_solution_improvement: 0 # stop the planner each time a solution improvement is found. Useful for debugging. Default: 0
+ use_strict_queue_ordering: 0 # sort edges in the queue at the end of the batch (0) or after each rewiring (1). Default: 0
+ find_approximate_solutions: 0 # track approximate solutions (1) or not (0). Default: 0
+ initial_inflation_factor: 1000000 # inflation factor for the initial search. Valid values: [1.0:0.01:1000000.0]. Default: 1000000
+ inflation_scaling_parameter: 10 # scaling parameter for the inflation factor update policy. Valid values: [1.0:0.01:1000000.0]. Default: 0
+ truncation_scaling_parameter: 5.0 # scaling parameter for the truncation factor update policy. Valid values: [1.0:0.01:1000000.0]. Default: 0
+ BITstar:
+ type: geometric::BITstar
+ use_k_nearest: 1 # whether to use a k-nearest RGG connection model (1) or an r-disc model (0). Default: 1
+ rewire_factor: 1.001 # rewire factor of the RGG. Valid values: [1.0:0.01:3.0]. Default: 1.001
+ samples_per_batch: 100 # batch size. Valid values: [1:1:1000]. Default: 100
+ use_graph_pruning: 1 # enable graph pruning (1) or not (0). Default: 1
+ prune_threshold_as_fractional_cost_change: 0.1 # fractional change in the solution cost AND problem measure necessary for pruning to occur. Default: 0.1
+ delay_rewiring_to_first_solution: 0 # delay (1) or not (0) rewiring until a solution is found. Default: 0
+ use_just_in_time_sampling: 0 # delay the generation of samples until they are * necessary. Only works with r-disc connection and path length minimization. Default: 0
+ drop_unconnected_samples_on_prune: 0 # drop unconnected samples when pruning, regardless of their heuristic value. Default: 0
+ stop_on_each_solution_improvement: 0 # stop the planner each time a solution improvement is found. Useful for debugging. Default: 0
+ use_strict_queue_ordering: 0 # sort edges in the queue at the end of the batch (0) or after each rewiring (1). Default: 0
+ find_approximate_solutions: 0 # track approximate solutions (1) or not (0). Default: 0
+summit:
+ planner_configs:
+ - AnytimePathShortening
+ - SBL
+ - EST
+ - LBKPIECE
+ - BKPIECE
+ - KPIECE
+ - RRT
+ - RRTConnect
+ - RRTstar
+ - TRRT
+ - PRM
+ - PRMstar
+ - FMT
+ - BFMT
+ - PDST
+ - STRIDE
+ - BiTRRT
+ - LBTRRT
+ - BiEST
+ - ProjEST
+ - LazyPRM
+ - LazyPRMstar
+ - SPARS
+ - SPARStwo
+ - AITstar
+ - ABITstar
+ - BITstar
+ projection_evaluator: joints(joint0,joint1)
+ longest_valid_segment_fraction: 0.005
+hand:
+ planner_configs:
+ - AnytimePathShortening
+ - SBL
+ - EST
+ - LBKPIECE
+ - BKPIECE
+ - KPIECE
+ - RRT
+ - RRTConnect
+ - RRTstar
+ - TRRT
+ - PRM
+ - PRMstar
+ - FMT
+ - BFMT
+ - PDST
+ - STRIDE
+ - BiTRRT
+ - LBTRRT
+ - BiEST
+ - ProjEST
+ - LazyPRM
+ - LazyPRMstar
+ - SPARS
+ - SPARStwo
+ - AITstar
+ - ABITstar
+ - BITstar
diff --git a/config/ros_controllers.yaml b/config/ros_controllers.yaml
new file mode 100644
index 0000000..21458cb
--- /dev/null
+++ b/config/ros_controllers.yaml
@@ -0,0 +1,40 @@
+arm_position_controller:
+ type: position_controllers/JointTrajectoryController
+ joints:
+ - joint0
+ - joint1
+ - joint2
+ - joint3
+ - joint4
+ - end_effector_joint
+ gains:
+ joint0:
+ p: 100
+ d: 1
+ i: 1
+ i_clamp: 1
+ joint1:
+ p: 100
+ d: 1
+ i: 1
+ i_clamp: 1
+ joint2:
+ p: 100
+ d: 1
+ i: 1
+ i_clamp: 1
+ joint3:
+ p: 100
+ d: 1
+ i: 1
+ i_clamp: 1
+ joint4:
+ p: 100
+ d: 1
+ i: 1
+ i_clamp: 1
+ end_effector_joint:
+ p: 100
+ d: 1
+ i: 1
+ i_clamp: 1
\ No newline at end of file
diff --git a/config/sensors_3d.yaml b/config/sensors_3d.yaml
new file mode 100644
index 0000000..51010a3
--- /dev/null
+++ b/config/sensors_3d.yaml
@@ -0,0 +1,2 @@
+sensors:
+ []
\ No newline at end of file
diff --git a/config/simple_moveit_controllers.yaml b/config/simple_moveit_controllers.yaml
new file mode 100644
index 0000000..d1c157b
--- /dev/null
+++ b/config/simple_moveit_controllers.yaml
@@ -0,0 +1,12 @@
+controller_list:
+ - name: arm_position_controller
+ action_ns: follow_joint_trajectory
+ type: FollowJointTrajectory
+ default: True
+ joints:
+ - joint0
+ - joint1
+ - joint2
+ - joint3
+ - joint4
+ - end_effector_joint
\ No newline at end of file
diff --git a/config/stomp_planning.yaml b/config/stomp_planning.yaml
new file mode 100644
index 0000000..4ec5772
--- /dev/null
+++ b/config/stomp_planning.yaml
@@ -0,0 +1,78 @@
+stomp/summit:
+ group_name: summit
+ optimization:
+ num_timesteps: 60
+ num_iterations: 40
+ num_iterations_after_valid: 0
+ num_rollouts: 30
+ max_rollouts: 30
+ initialization_method: 1 # [1 : LINEAR_INTERPOLATION, 2 : CUBIC_POLYNOMIAL, 3 : MININUM_CONTROL_COST]
+ control_cost_weight: 0.0
+ task:
+ noise_generator:
+ - class: stomp_moveit/NormalDistributionSampling
+ stddev: [0.05, 0.05, 0.05, 0.05, 0.05, 0.05]
+ cost_functions:
+ - class: stomp_moveit/CollisionCheck
+ collision_penalty: 1.0
+ cost_weight: 1.0
+ kernel_window_percentage: 0.2
+ longest_valid_joint_move: 0.05
+ noisy_filters:
+ - class: stomp_moveit/JointLimits
+ lock_start: True
+ lock_goal: True
+ - class: stomp_moveit/MultiTrajectoryVisualization
+ line_width: 0.02
+ rgb: [255, 255, 0]
+ marker_array_topic: stomp_trajectories
+ marker_namespace: noisy
+ update_filters:
+ - class: stomp_moveit/PolynomialSmoother
+ poly_order: 6
+ - class: stomp_moveit/TrajectoryVisualization
+ line_width: 0.05
+ rgb: [0, 191, 255]
+ error_rgb: [255, 0, 0]
+ publish_intermediate: True
+ marker_topic: stomp_trajectory
+ marker_namespace: optimized
+stomp/hand:
+ group_name: hand
+ optimization:
+ num_timesteps: 60
+ num_iterations: 40
+ num_iterations_after_valid: 0
+ num_rollouts: 30
+ max_rollouts: 30
+ initialization_method: 1 # [1 : LINEAR_INTERPOLATION, 2 : CUBIC_POLYNOMIAL, 3 : MININUM_CONTROL_COST]
+ control_cost_weight: 0.0
+ task:
+ noise_generator:
+ - class: stomp_moveit/NormalDistributionSampling
+ stddev: [0.05]
+ cost_functions:
+ - class: stomp_moveit/CollisionCheck
+ collision_penalty: 1.0
+ cost_weight: 1.0
+ kernel_window_percentage: 0.2
+ longest_valid_joint_move: 0.05
+ noisy_filters:
+ - class: stomp_moveit/JointLimits
+ lock_start: True
+ lock_goal: True
+ - class: stomp_moveit/MultiTrajectoryVisualization
+ line_width: 0.02
+ rgb: [255, 255, 0]
+ marker_array_topic: stomp_trajectories
+ marker_namespace: noisy
+ update_filters:
+ - class: stomp_moveit/PolynomialSmoother
+ poly_order: 6
+ - class: stomp_moveit/TrajectoryVisualization
+ line_width: 0.05
+ rgb: [0, 191, 255]
+ error_rgb: [255, 0, 0]
+ publish_intermediate: True
+ marker_topic: stomp_trajectory
+ marker_namespace: optimized
\ No newline at end of file
diff --git a/launch/ASY, ROBOTIC ARM 2024, URDF_moveit_sensor_manager.launch.xml b/launch/ASY, ROBOTIC ARM 2024, URDF_moveit_sensor_manager.launch.xml
new file mode 100644
index 0000000..5d02698
--- /dev/null
+++ b/launch/ASY, ROBOTIC ARM 2024, URDF_moveit_sensor_manager.launch.xml
@@ -0,0 +1,3 @@
+
+
+
diff --git a/launch/chomp_planning_pipeline.launch.xml b/launch/chomp_planning_pipeline.launch.xml
new file mode 100644
index 0000000..1f0aeb2
--- /dev/null
+++ b/launch/chomp_planning_pipeline.launch.xml
@@ -0,0 +1,21 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/launch/default_warehouse_db.launch b/launch/default_warehouse_db.launch
new file mode 100644
index 0000000..6a5fc55
--- /dev/null
+++ b/launch/default_warehouse_db.launch
@@ -0,0 +1,15 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/launch/demo.launch b/launch/demo.launch
new file mode 100644
index 0000000..7277e15
--- /dev/null
+++ b/launch/demo.launch
@@ -0,0 +1,67 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+ [move_group/fake_controller_joint_states]
+
+
+
+ [move_group/fake_controller_joint_states]
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/launch/demo_gazebo.launch b/launch/demo_gazebo.launch
new file mode 100644
index 0000000..0ef8f95
--- /dev/null
+++ b/launch/demo_gazebo.launch
@@ -0,0 +1,21 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/launch/fake_moveit_controller_manager.launch.xml b/launch/fake_moveit_controller_manager.launch.xml
new file mode 100644
index 0000000..57a3492
--- /dev/null
+++ b/launch/fake_moveit_controller_manager.launch.xml
@@ -0,0 +1,12 @@
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/launch/gazebo.launch b/launch/gazebo.launch
new file mode 100644
index 0000000..e5c53ce
--- /dev/null
+++ b/launch/gazebo.launch
@@ -0,0 +1,34 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/launch/joystick_control.launch b/launch/joystick_control.launch
new file mode 100644
index 0000000..9411f6e
--- /dev/null
+++ b/launch/joystick_control.launch
@@ -0,0 +1,17 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/launch/move_group.launch b/launch/move_group.launch
new file mode 100644
index 0000000..7ba6fc8
--- /dev/null
+++ b/launch/move_group.launch
@@ -0,0 +1,105 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/launch/moveit.rviz b/launch/moveit.rviz
new file mode 100644
index 0000000..aadeaab
--- /dev/null
+++ b/launch/moveit.rviz
@@ -0,0 +1,131 @@
+Panels:
+ - Class: rviz/Displays
+ Help Height: 84
+ Name: Displays
+ Property Tree Widget:
+ Expanded:
+ - /MotionPlanning1
+ Splitter Ratio: 0.5
+ Tree Height: 226
+ - Class: rviz/Help
+ Name: Help
+ - Class: rviz/Views
+ Expanded:
+ - /Current View1
+ Name: Views
+ Splitter Ratio: 0.5
+Visualization Manager:
+ Class: ""
+ Displays:
+ - Alpha: 0.5
+ Cell Size: 1
+ Class: rviz/Grid
+ Color: 160; 160; 164
+ Enabled: true
+ Line Style:
+ Line Width: 0.03
+ 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
+ - Class: moveit_rviz_plugin/MotionPlanning
+ Enabled: true
+ Name: MotionPlanning
+ Planned Path:
+ Links: ~
+ Loop Animation: true
+ Robot Alpha: 0.5
+ Show Robot Collision: false
+ Show Robot Visual: true
+ Show Trail: false
+ State Display Time: 0.05 s
+ Trajectory Topic: move_group/display_planned_path
+ Planning Metrics:
+ Payload: 1
+ Show Joint Torques: false
+ Show Manipulability: false
+ Show Manipulability Index: false
+ Show Weight Limit: false
+ Planning Request:
+ Colliding Link Color: 255; 0; 0
+ Goal State Alpha: 1
+ Goal State Color: 250; 128; 0
+ Interactive Marker Size: 0
+ Joint Violation Color: 255; 0; 255
+ Query Goal State: true
+ Query Start State: false
+ Show Workspace: false
+ Start State Alpha: 1
+ Start State Color: 0; 255; 0
+ Planning Scene Topic: move_group/monitored_planning_scene
+ Robot Description: robot_description
+ Scene Geometry:
+ Scene Alpha: 1
+ Show Scene Geometry: true
+ Voxel Coloring: Z-Axis
+ Voxel Rendering: Occupied Voxels
+ Scene Robot:
+ Attached Body Color: 150; 50; 150
+ Links: ~
+ Robot Alpha: 0.5
+ Show Scene Robot: true
+ Value: true
+ Enabled: true
+ Global Options:
+ Background Color: 48; 48; 48
+ Fixed Frame: dummy
+ Name: root
+ Tools:
+ - Class: rviz/Interact
+ Hide Inactive Objects: true
+ - Class: rviz/MoveCamera
+ - Class: rviz/Select
+ Value: true
+ Views:
+ Current:
+ Class: rviz/Orbit
+ Distance: 2.0
+ Enable Stereo Rendering:
+ Stereo Eye Separation: 0.06
+ Stereo Focal Distance: 1
+ Swap Stereo Eyes: false
+ Value: false
+ Field of View: 0.75
+ Focal Point:
+ X: -0.1
+ Y: 0.25
+ Z: 0.30
+ Focal Shape Fixed Size: true
+ Focal Shape Size: 0.05
+ Invert Z Axis: false
+ Name: Current View
+ Near Clip Distance: 0.01
+ Pitch: 0.5
+ Target Frame: dummy
+ Yaw: -0.6232355833053589
+ Saved: ~
+Window Geometry:
+ Displays:
+ collapsed: false
+ Height: 848
+ Help:
+ collapsed: false
+ Hide Left Dock: false
+ Hide Right Dock: false
+ MotionPlanning:
+ collapsed: false
+ MotionPlanning - Trajectory Slider:
+ collapsed: false
+ QMainWindow State: 000000ff00000000fd0000000100000000000001f0000002f6fc0200000007fb000000100044006900730070006c006100790073010000003d00000173000000c900fffffffb0000000800480065006c00700000000342000000bb0000006e00fffffffb0000000a00560069006500770073000000010c000000a4000000a400fffffffb0000000c00430061006d00650072006100000002ff000001610000000000000000fb0000001e004d006f00740069006f006e00200050006c0061006e006e0069006e00670100000374000001890000000000000000fb00000044004d006f00740069006f006e0050006c0061006e006e0069006e00670020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000001600000016fb0000001c004d006f00740069006f006e0050006c0061006e006e0069006e006701000001b60000017d0000017d00ffffff00000315000002f600000001000000020000000100000002fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
+ Views:
+ collapsed: false
+ Width: 1291
+ X: 454
+ Y: 25
diff --git a/launch/moveit_rviz.launch b/launch/moveit_rviz.launch
new file mode 100644
index 0000000..a4605c0
--- /dev/null
+++ b/launch/moveit_rviz.launch
@@ -0,0 +1,15 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/launch/ompl-chomp_planning_pipeline.launch.xml b/launch/ompl-chomp_planning_pipeline.launch.xml
new file mode 100644
index 0000000..bc2ebd3
--- /dev/null
+++ b/launch/ompl-chomp_planning_pipeline.launch.xml
@@ -0,0 +1,20 @@
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/launch/ompl_planning_pipeline.launch.xml b/launch/ompl_planning_pipeline.launch.xml
new file mode 100644
index 0000000..6a7c200
--- /dev/null
+++ b/launch/ompl_planning_pipeline.launch.xml
@@ -0,0 +1,24 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/launch/pilz_industrial_motion_planner_planning_pipeline.launch.xml b/launch/pilz_industrial_motion_planner_planning_pipeline.launch.xml
new file mode 100644
index 0000000..c7c4cf5
--- /dev/null
+++ b/launch/pilz_industrial_motion_planner_planning_pipeline.launch.xml
@@ -0,0 +1,15 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/launch/planning_context.launch b/launch/planning_context.launch
new file mode 100644
index 0000000..0958b25
--- /dev/null
+++ b/launch/planning_context.launch
@@ -0,0 +1,26 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/launch/planning_pipeline.launch.xml b/launch/planning_pipeline.launch.xml
new file mode 100644
index 0000000..4b4d0d6
--- /dev/null
+++ b/launch/planning_pipeline.launch.xml
@@ -0,0 +1,10 @@
+
+
+
+
+
+
+
+
+
diff --git a/launch/ros_control_moveit_controller_manager.launch.xml b/launch/ros_control_moveit_controller_manager.launch.xml
new file mode 100644
index 0000000..9ebc91c
--- /dev/null
+++ b/launch/ros_control_moveit_controller_manager.launch.xml
@@ -0,0 +1,4 @@
+
+
+
+
diff --git a/launch/ros_controllers.launch b/launch/ros_controllers.launch
new file mode 100644
index 0000000..03553b8
--- /dev/null
+++ b/launch/ros_controllers.launch
@@ -0,0 +1,11 @@
+
+
+
+
+
+
+
+
+
+
diff --git a/launch/run_benchmark_ompl.launch b/launch/run_benchmark_ompl.launch
new file mode 100644
index 0000000..190e775
--- /dev/null
+++ b/launch/run_benchmark_ompl.launch
@@ -0,0 +1,21 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/launch/sensor_manager.launch.xml b/launch/sensor_manager.launch.xml
new file mode 100644
index 0000000..b937b39
--- /dev/null
+++ b/launch/sensor_manager.launch.xml
@@ -0,0 +1,17 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/launch/setup_assistant.launch b/launch/setup_assistant.launch
new file mode 100644
index 0000000..5665bf3
--- /dev/null
+++ b/launch/setup_assistant.launch
@@ -0,0 +1,16 @@
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/launch/simple_moveit_controller_manager.launch.xml b/launch/simple_moveit_controller_manager.launch.xml
new file mode 100644
index 0000000..8b5ab2f
--- /dev/null
+++ b/launch/simple_moveit_controller_manager.launch.xml
@@ -0,0 +1,8 @@
+
+
+
+
+
+
+
+
diff --git a/launch/stomp_planning_pipeline.launch.xml b/launch/stomp_planning_pipeline.launch.xml
new file mode 100644
index 0000000..c3c2c9f
--- /dev/null
+++ b/launch/stomp_planning_pipeline.launch.xml
@@ -0,0 +1,23 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/launch/trajectory_execution.launch.xml b/launch/trajectory_execution.launch.xml
new file mode 100644
index 0000000..20c3dfc
--- /dev/null
+++ b/launch/trajectory_execution.launch.xml
@@ -0,0 +1,23 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/launch/warehouse.launch b/launch/warehouse.launch
new file mode 100644
index 0000000..0712e67
--- /dev/null
+++ b/launch/warehouse.launch
@@ -0,0 +1,15 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/launch/warehouse_settings.launch.xml b/launch/warehouse_settings.launch.xml
new file mode 100644
index 0000000..e473b08
--- /dev/null
+++ b/launch/warehouse_settings.launch.xml
@@ -0,0 +1,16 @@
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
diff --git a/package.xml b/package.xml
new file mode 100644
index 0000000..cdc1e30
--- /dev/null
+++ b/package.xml
@@ -0,0 +1,41 @@
+
+
+ moveitarm
+ 0.3.0
+
+ An automatically generated package with all the configuration and launch files for using the ASY, ROBOTIC ARM 2024, URDF with the MoveIt Motion Planning Framework
+
+ joshua blanch
+ joshua blanch
+
+ BSD
+
+ http://moveit.ros.org/
+ https://github.com/moveit/moveit/issues
+ https://github.com/moveit/moveit
+
+ catkin
+
+ moveit_ros_move_group
+ moveit_fake_controller_manager
+ moveit_kinematics
+ moveit_planners
+ moveit_ros_visualization
+ moveit_setup_assistant
+ moveit_simple_controller_manager
+ joint_state_publisher
+ joint_state_publisher_gui
+ robot_state_publisher
+ rviz
+ tf2_ros
+ xacro
+
+
+
+
+
+ uvicarm2024
+
+
+