diff --git a/.setup_assistant b/.setup_assistant
index f54adbf..37da26c 100644
--- a/.setup_assistant
+++ b/.setup_assistant
@@ -1,7 +1,7 @@
moveit_setup_assistant_config:
URDF:
package: franka_description
- relative_path: robots/panda/panda.urdf.xacro
+ relative_path: robots/panda/panda_arm.urdf.xacro
xacro_args: hand:=true
SRDF:
relative_path: config/panda.srdf.xacro
diff --git a/CMakeLists.txt b/CMakeLists.txt
index 675c9ac..c69be73 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -1,10 +1,7 @@
-cmake_minimum_required(VERSION 3.1.3)
+cmake_minimum_required(VERSION 3.10.2)
project(panda_moveit_config)
+find_package(ament_cmake REQUIRED)
-find_package(catkin REQUIRED)
+ament_package()
-catkin_package()
-
-install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
- PATTERN "setup_assistant.launch" EXCLUDE)
-install(DIRECTORY config DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION})
+install(DIRECTORY config DESTINATION share/${PROJECT_NAME})
diff --git a/config/chomp_planning.yaml b/config/chomp_planning.yaml
index eb9c912..306d33b 100644
--- a/config/chomp_planning.yaml
+++ b/config/chomp_planning.yaml
@@ -1,18 +1,36 @@
+planning_plugin: chomp_interface/CHOMPPlanner
+request_adapters: >-
+ default_planner_request_adapters/AddTimeOptimalParameterization
+ default_planner_request_adapters/FixWorkspaceBounds
+ default_planner_request_adapters/FixStartStateBounds
+ default_planner_request_adapters/FixStartStateCollision
+ default_planner_request_adapters/FixStartStatePathConstraints
+start_state_max_bounds_error: 0.1
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
+animate_path: true
+add_randomness: false
smoothness_cost_velocity: 0.0
smoothness_cost_acceleration: 1.0
smoothness_cost_jerk: 0.0
+hmc_discretization: 0.01
+hmc_stochasticity: 0.01
+hmc_annealing_factor: 0.99
+use_hamiltonian_monte_carlo: false
ridge_factor: 0.0
use_pseudo_inverse: false
pseudo_inverse_ridge_factor: 1e-4
+animate_endeffector: false
+animate_endeffector_segment: "panda_rightfinger"
joint_update_limit: 0.1
collision_clearance: 0.2
collision_threshold: 0.07
+random_jump_amount: 1.0
use_stochastic_descent: true
enable_failure_recovery: false
max_recovery_attempts: 5
+trajectory_initialization_method: "quintic-spline"
diff --git a/config/joint_limits.yaml b/config/joint_limits.yaml
index 9bdaadd..ff11cba 100644
--- a/config/joint_limits.yaml
+++ b/config/joint_limits.yaml
@@ -59,4 +59,13 @@ joint_limits:
max_velocity: 2.6100
has_acceleration_limits: true
max_acceleration: 5
-
+ panda_finger_joint1:
+ has_velocity_limits: true
+ max_velocity: 0.1
+ has_acceleration_limits: false
+ max_acceleration: 0.0
+ panda_finger_joint2:
+ has_velocity_limits: true
+ max_velocity: 0.1
+ has_acceleration_limits: false
+ max_acceleration: 0.0
diff --git a/config/lerp_planning.yaml b/config/lerp_planning.yaml
index 9d2eebd..758a63d 100644
--- a/config/lerp_planning.yaml
+++ b/config/lerp_planning.yaml
@@ -1 +1,9 @@
+planning_plugin: lerp_interface/LERPPlanner
+request_adapters: >-
+ default_planner_request_adapters/AddTimeOptimalParameterization
+ default_planner_request_adapters/FixWorkspaceBounds
+ default_planner_request_adapters/FixStartStateBounds
+ default_planner_request_adapters/FixStartStateCollision
+ default_planner_request_adapters/FixStartStatePathConstraints
+start_state_max_bounds_error: 0.1
num_steps: 40
diff --git a/config/moveit_controllers.yaml b/config/moveit_controllers.yaml
new file mode 100644
index 0000000..da2438d
--- /dev/null
+++ b/config/moveit_controllers.yaml
@@ -0,0 +1,32 @@
+trajectory_execution:
+ allowed_execution_duration_scaling: 1.2
+ allowed_goal_duration_margin: 0.5
+ allowed_start_tolerance: 0.01
+
+moveit_controller_manager: moveit_simple_controller_manager/MoveItSimpleControllerManager
+
+moveit_simple_controller_manager:
+ controller_names:
+ - panda_arm_controller
+ - panda_hand_controller
+
+ panda_arm_controller:
+ action_ns: follow_joint_trajectory
+ type: FollowJointTrajectory
+ default: true
+ joints:
+ - panda_joint1
+ - panda_joint2
+ - panda_joint3
+ - panda_joint4
+ - panda_joint5
+ - panda_joint6
+ - panda_joint7
+
+ panda_hand_controller:
+ action_ns: gripper_cmd
+ type: GripperCommand
+ default: true
+ joints:
+ - panda_finger_joint1
+
diff --git a/config/ompl_planning.yaml b/config/ompl_planning.yaml
index 32b496e..ac7c10c 100644
--- a/config/ompl_planning.yaml
+++ b/config/ompl_planning.yaml
@@ -1,49 +1,42 @@
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:
+ SBLkConfigDefault:
type: geometric::SBL
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
- EST:
+ ESTkConfigDefault:
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:
+ LBKPIECEkConfigDefault:
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:
+ BKPIECEkConfigDefault:
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
+ border_fraction: 0.9 # Fraction fof 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:
+ KPIECEkConfigDefault:
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:
+ RRTkConfigDefault:
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:
+ RRTConnectkConfigDefault:
type: geometric::RRTConnect
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
- RRTstar:
+ RRTstarkConfigDefault:
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:
+ TRRTkConfigDefault:
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
@@ -54,12 +47,12 @@ planner_configs:
frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup()
frountierNodeRatio: 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:
+ PRMkConfigDefault:
type: geometric::PRM
max_nearest_neighbors: 10 # use k nearest neighbors. default: 10
- PRMstar:
+ PRMstarkConfigDefault:
type: geometric::PRMstar
- FMT:
+ FMTkConfigDefault:
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
@@ -67,7 +60,7 @@ planner_configs:
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:
+ BFMTkConfigDefault:
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
@@ -77,9 +70,9 @@ planner_configs:
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:
+ PDSTkConfigDefault:
type: geometric::PDST
- STRIDE:
+ STRIDEkConfigDefault:
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
@@ -90,7 +83,7 @@ planner_configs:
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:
+ BiTRRTkConfigDefault:
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
@@ -98,87 +91,88 @@ planner_configs:
frountier_threshold: 0.0 # dist new state to nearest neighbor to disqualify as frontier. default: 0.0 set in setup()
frountier_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:
+ LBTRRTkConfigDefault:
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:
+ BiESTkConfigDefault:
type: geometric::BiEST
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
- ProjEST:
+ ProjESTkConfigDefault:
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:
+ LazyPRMkConfigDefault:
type: geometric::LazyPRM
range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup()
- LazyPRMstar:
+ LazyPRMstarkConfigDefault:
type: geometric::LazyPRMstar
- SPARS:
+ SPARSkConfigDefault:
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:
+ SPARStwokConfigDefault:
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
-$(arg arm_id)_arm: &arm_config
+ TrajOptDefault:
+ type: geometric::TrajOpt
+
+panda_arm:
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
- projection_evaluator: joints($(arg arm_id)_joint1,$(arg arm_id)_joint2)
- longest_valid_segment_fraction: 0.005
-$(arg arm_id)_manipulator: *arm_config
-$(arg arm_id)_hand:
+ - SBLkConfigDefault
+ - ESTkConfigDefault
+ - LBKPIECEkConfigDefault
+ - BKPIECEkConfigDefault
+ - KPIECEkConfigDefault
+ - RRTkConfigDefault
+ - RRTConnectkConfigDefault
+ - RRTstarkConfigDefault
+ - TRRTkConfigDefault
+ - PRMkConfigDefault
+ - PRMstarkConfigDefault
+ - FMTkConfigDefault
+ - BFMTkConfigDefault
+ - PDSTkConfigDefault
+ - STRIDEkConfigDefault
+ - BiTRRTkConfigDefault
+ - LBTRRTkConfigDefault
+ - BiESTkConfigDefault
+ - ProjESTkConfigDefault
+ - LazyPRMkConfigDefault
+ - LazyPRMstarkConfigDefault
+ - SPARSkConfigDefault
+ - SPARStwokConfigDefault
+ - TrajOptDefault
+panda_arm_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
+ - SBLkConfigDefault
+ - ESTkConfigDefault
+ - LBKPIECEkConfigDefault
+ - BKPIECEkConfigDefault
+ - KPIECEkConfigDefault
+ - RRTkConfigDefault
+ - RRTConnectkConfigDefault
+ - RRTstarkConfigDefault
+ - TRRTkConfigDefault
+ - PRMkConfigDefault
+ - PRMstarkConfigDefault
+ - FMTkConfigDefault
+ - BFMTkConfigDefault
+ - PDSTkConfigDefault
+ - STRIDEkConfigDefault
+ - BiTRRTkConfigDefault
+ - LBTRRTkConfigDefault
+ - BiESTkConfigDefault
+ - ProjESTkConfigDefault
+ - LazyPRMkConfigDefault
+ - LazyPRMstarkConfigDefault
+ - SPARSkConfigDefault
+ - SPARStwokConfigDefault
+ - TrajOptDefault
+
diff --git a/config/cartesian_limits.yaml b/config/pilz_cartesian_limits.yaml
similarity index 100%
rename from config/cartesian_limits.yaml
rename to config/pilz_cartesian_limits.yaml
diff --git a/config/pilz_industrial_motion_planner_planning.yaml b/config/pilz_industrial_motion_planner_planning.yaml
new file mode 100644
index 0000000..6402ab9
--- /dev/null
+++ b/config/pilz_industrial_motion_planner_planning.yaml
@@ -0,0 +1,10 @@
+planning_plugin: pilz_industrial_motion_planner/CommandPlanner
+request_adapters: >-
+ default_planner_request_adapters/FixWorkspaceBounds
+ default_planner_request_adapters/FixStartStateBounds
+ default_planner_request_adapters/FixStartStateCollision
+ default_planner_request_adapters/FixStartStatePathConstraints
+default_planner_config: PTP
+capabilities: >-
+ pilz_industrial_motion_planner/MoveGroupSequenceAction
+ pilz_industrial_motion_planner/MoveGroupSequenceService
diff --git a/config/ros2_controllers.yaml b/config/ros2_controllers.yaml
new file mode 100644
index 0000000..617efbf
--- /dev/null
+++ b/config/ros2_controllers.yaml
@@ -0,0 +1,41 @@
+controller_manager:
+ ros__parameters:
+ update_rate: 1000 # Hz
+
+ panda_arm_controller:
+ type: joint_trajectory_controller/JointTrajectoryController
+
+ panda_hand_controller:
+ type: position_controllers/GripperActionController
+
+ joint_state_broadcaster:
+ type: joint_state_broadcaster/JointStateBroadcaster
+
+
+panda_arm_controller:
+ ros__parameters:
+ command_interfaces:
+ - effort
+ state_interfaces:
+ - position
+ - velocity
+ joints:
+ - panda_joint1
+ - panda_joint2
+ - panda_joint3
+ - panda_joint4
+ - panda_joint5
+ - panda_joint6
+ - panda_joint7
+ gains:
+ panda_joint1: { p: 600., d: 30., i: 0., i_clamp: 1. }
+ panda_joint2: { p: 600., d: 30., i: 0., i_clamp: 1. }
+ panda_joint3: { p: 600., d: 30., i: 0., i_clamp: 1. }
+ panda_joint4: { p: 600., d: 30., i: 0., i_clamp: 1. }
+ panda_joint5: { p: 250., d: 10., i: 0., i_clamp: 1. }
+ panda_joint6: { p: 150., d: 10., i: 0., i_clamp: 1. }
+ panda_joint7: { p: 50., d: 5., i: 0., i_clamp: 1. }
+
+panda_hand_controller:
+ ros__parameters:
+ joint: panda_finger_joint1
diff --git a/config/sensors_kinect_depthmap.yaml b/config/sensors_kinect_depthmap.yaml
index fc4d7d9..9538fe0 100644
--- a/config/sensors_kinect_depthmap.yaml
+++ b/config/sensors_kinect_depthmap.yaml
@@ -9,4 +9,3 @@ sensors:
padding_offset: 0.03
max_update_rate: 1.0
filtered_cloud_topic: filtered_cloud
- ns: kinect
diff --git a/config/sensors_kinect_pointcloud.yaml b/config/sensors_kinect_pointcloud.yaml
index dd7dbbb..92e7095 100644
--- a/config/sensors_kinect_pointcloud.yaml
+++ b/config/sensors_kinect_pointcloud.yaml
@@ -7,4 +7,3 @@ sensors:
padding_scale: 1.0
max_update_rate: 1.0
filtered_cloud_topic: filtered_cloud
- ns: kinect
diff --git a/config/simple_moveit_controllers.yaml b/config/simple_moveit_controllers.yaml
deleted file mode 100644
index 19a874b..0000000
--- a/config/simple_moveit_controllers.yaml
+++ /dev/null
@@ -1,19 +0,0 @@
-controller_list:
- - name: $(arg transmission)_joint_trajectory_controller
- action_ns: follow_joint_trajectory
- type: FollowJointTrajectory
- default: True
- joints:
- - $(arg arm_id)_joint1
- - $(arg arm_id)_joint2
- - $(arg arm_id)_joint3
- - $(arg arm_id)_joint4
- - $(arg arm_id)_joint5
- - $(arg arm_id)_joint6
- - $(arg arm_id)_joint7
- - name: franka_gripper
- action_ns: gripper_action
- type: GripperCommand
- default: True
- joints:
- - $(arg arm_id)_finger_joint1
diff --git a/config/stomp_planning.yaml b/config/stomp_planning.yaml
deleted file mode 100644
index 7084f2f..0000000
--- a/config/stomp_planning.yaml
+++ /dev/null
@@ -1,37 +0,0 @@
-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.8, 1.0, 0.8, 0.4, 0.4, 0.4]
- 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
diff --git a/config/trajopt_planning.yaml b/config/trajopt_planning.yaml
index 6c6ea43..dfe67f6 100644
--- a/config/trajopt_planning.yaml
+++ b/config/trajopt_planning.yaml
@@ -1,3 +1,11 @@
+planning_plugin: trajopt_interface/TrajOptPlanner
+request_adapters: >-
+ default_planner_request_adapters/AddTimeOptimalParameterization
+ default_planner_request_adapters/FixWorkspaceBounds
+ default_planner_request_adapters/FixStartStateBounds
+ default_planner_request_adapters/FixStartStateCollision
+ default_planner_request_adapters/FixStartStatePathConstraints
+start_state_max_bounds_error: 0.1
trajopt_param:
improve_ratio_threshold: 0.25 # minimum ratio true_improve/approx_improve to accept step. [Research Paper] TrueImprove/ModelImprove > c
min_trust_box_size: 1e-4 # if trust region gets any smaller, exit and report convergence. [Research Paper] xtol
diff --git a/config/ros_controllers.yaml b/launch/.gitkeep
similarity index 100%
rename from config/ros_controllers.yaml
rename to launch/.gitkeep
diff --git a/launch/chomp_planning_pipeline.launch.xml b/launch/chomp_planning_pipeline.launch.xml
deleted file mode 100644
index 39e645f..0000000
--- a/launch/chomp_planning_pipeline.launch.xml
+++ /dev/null
@@ -1,23 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/launch/default_warehouse_db.launch b/launch/default_warehouse_db.launch
deleted file mode 100644
index dc1aea7..0000000
--- a/launch/default_warehouse_db.launch
+++ /dev/null
@@ -1,15 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/launch/demo.launch b/launch/demo.launch
deleted file mode 100644
index 543cb19..0000000
--- a/launch/demo.launch
+++ /dev/null
@@ -1,73 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
- [move_group/fake_controller_joint_states]
-
-
-
- [move_group/fake_controller_joint_states]
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/launch/demo_chomp.launch b/launch/demo_chomp.launch
deleted file mode 100644
index a3051a8..0000000
--- a/launch/demo_chomp.launch
+++ /dev/null
@@ -1,5 +0,0 @@
-
-
-
-
-
diff --git a/launch/demo_gazebo.launch b/launch/demo_gazebo.launch
deleted file mode 100644
index 2907f8f..0000000
--- a/launch/demo_gazebo.launch
+++ /dev/null
@@ -1,27 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/launch/demo_lerp.launch b/launch/demo_lerp.launch
deleted file mode 100644
index d5d8355..0000000
--- a/launch/demo_lerp.launch
+++ /dev/null
@@ -1,6 +0,0 @@
-
-
-
-
-
-
\ No newline at end of file
diff --git a/launch/demo_stomp.launch b/launch/demo_stomp.launch
deleted file mode 100644
index 0ae0551..0000000
--- a/launch/demo_stomp.launch
+++ /dev/null
@@ -1,5 +0,0 @@
-
-
-
-
-
diff --git a/launch/fake_moveit_controller_manager.launch.xml b/launch/fake_moveit_controller_manager.launch.xml
deleted file mode 100644
index 53811ba..0000000
--- a/launch/fake_moveit_controller_manager.launch.xml
+++ /dev/null
@@ -1,12 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/launch/franka_control.launch b/launch/franka_control.launch
deleted file mode 100644
index d3e9023..0000000
--- a/launch/franka_control.launch
+++ /dev/null
@@ -1,22 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/launch/joystick_control.launch b/launch/joystick_control.launch
deleted file mode 100644
index 9411f6e..0000000
--- a/launch/joystick_control.launch
+++ /dev/null
@@ -1,17 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/launch/lerp_planning_pipeline.launch.xml b/launch/lerp_planning_pipeline.launch.xml
deleted file mode 100644
index c119357..0000000
--- a/launch/lerp_planning_pipeline.launch.xml
+++ /dev/null
@@ -1,22 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/launch/move_group.launch b/launch/move_group.launch
deleted file mode 100644
index 7d511f3..0000000
--- a/launch/move_group.launch
+++ /dev/null
@@ -1,111 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/launch/moveit.rviz b/launch/moveit.rviz
deleted file mode 100644
index 82d21c7..0000000
--- a/launch/moveit.rviz
+++ /dev/null
@@ -1,131 +0,0 @@
-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: panda_link0
- 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: panda_link0
- 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_empty.rviz b/launch/moveit_empty.rviz
deleted file mode 100644
index 9014d11..0000000
--- a/launch/moveit_empty.rviz
+++ /dev/null
@@ -1,99 +0,0 @@
-Panels:
- - Class: rviz/Displays
- Help Height: 84
- Name: Displays
- Property Tree Widget:
- Expanded: ~
- Splitter Ratio: 0.5
- Tree Height: 613
- - Class: rviz/Help
- Name: Help
- - Class: rviz/Views
- Expanded:
- - /Current View1
- Name: Views
- Splitter Ratio: 0.5
-Preferences:
- PromptSaveOnExit: true
-Toolbars:
- toolButtonStyle: 2
-Visualization Manager:
- Class: ""
- Displays:
- - Alpha: 0.5
- Cell Size: 1
- Class: rviz/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
- - Class: rviz/MarkerArray
- Enabled: true
- Marker Topic: rviz_visual_tools
- Name: MarkerArray
- Namespaces:
- {}
- Queue Size: 100
- Value: true
- Enabled: true
- Global Options:
- Background Color: 48; 48; 48
- Default Light: true
- Fixed Frame: panda_link0
- Frame Rate: 30
- Name: root
- Tools:
- - Class: rviz/Interact
- Hide Inactive Objects: true
- - Class: rviz/MoveCamera
- - Class: rviz/Select
- - Class: rviz_visual_tools/KeyTool
- Value: true
- Views:
- Current:
- Class: rviz/Orbit
- Distance: 2
- Enable Stereo Rendering:
- Stereo Eye Separation: 0.05999999865889549
- Stereo Focal Distance: 1
- Swap Stereo Eyes: false
- Value: false
- Field of View: 0.75
- Focal Point:
- X: -0.10000000149011612
- Y: 0.25
- Z: 0.30000001192092896
- Focal Shape Fixed Size: true
- Focal Shape Size: 0.05000000074505806
- Invert Z Axis: false
- Name: Current View
- Near Clip Distance: 0.009999999776482582
- Pitch: 0.5
- Target Frame: panda_link0
- Yaw: -0.6232355833053589
- Saved: ~
-Window Geometry:
- Displays:
- collapsed: false
- Height: 848
- Help:
- collapsed: false
- Hide Left Dock: false
- Hide Right Dock: false
- QMainWindow State: 000000ff00000000fd0000000100000000000001f0000002f6fc020000000afb000000100044006900730070006c006100790073010000003d000002f6000000c900fffffffb0000000800480065006c00700000000342000000bb0000006e00fffffffb0000000a00560069006500770073000000010c000000a4000000a400fffffffb0000000c00430061006d00650072006100000002ff000001610000000000000000fb0000001e004d006f00740069006f006e00200050006c0061006e006e0069006e00670100000374000001890000000000000000fb00000044004d006f00740069006f006e0050006c0061006e006e0069006e00670020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000000000000000fb0000001c004d006f00740069006f006e0050006c0061006e006e0069006e006700000001ab000001880000000000000000fb000000280020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000000000000000fb00000024005200760069007a00560069007300750061006c0054006f006f006c007300470075006900000002f2000000410000000000000000fb0000003c005400720061006a006500630074006f007200790020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff000000000000000000000315000002f600000001000000020000000100000002fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
- Views:
- collapsed: false
- Width: 1291
- X: 444
- Y: 25
diff --git a/launch/moveit_rviz.launch b/launch/moveit_rviz.launch
deleted file mode 100644
index 89e0db9..0000000
--- a/launch/moveit_rviz.launch
+++ /dev/null
@@ -1,19 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/launch/moveit_scene.rviz b/launch/moveit_scene.rviz
deleted file mode 100644
index b9e16ad..0000000
--- a/launch/moveit_scene.rviz
+++ /dev/null
@@ -1,138 +0,0 @@
-Panels:
- - Class: rviz/Displays
- Help Height: 84
- Name: Displays
- Property Tree Widget:
- Expanded: ~
- Splitter Ratio: 0.5
- Tree Height: 542
- - Class: rviz/Help
- Name: Help
- - Class: rviz/Views
- Expanded:
- - /Current View1
- Name: Views
- Splitter Ratio: 0.5
- - Class: rviz_visual_tools/RvizVisualToolsGui
- Name: RvizVisualToolsGui
-Preferences:
- PromptSaveOnExit: true
-Toolbars:
- toolButtonStyle: 2
-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: rviz/MarkerArray
- Enabled: true
- Marker Topic: rviz_visual_tools
- Name: MarkerArray
- Namespaces:
- {}
- Queue Size: 100
- Value: true
- - Class: moveit_rviz_plugin/Trajectory
- Color Enabled: false
- Enabled: true
- Interrupt Display: false
- Links: ~
- Loop Animation: false
- Name: Trajectory
- Robot Alpha: 0.5
- Show Robot Collision: false
- Show Robot Visual: true
- Show Trail: false
- State Display Time: 3x
- Trail Step Size: 1
- Trajectory Topic: move_group/display_planned_path
- Value: true
- - Class: moveit_rviz_plugin/PlanningScene
- Enabled: true
- Move Group Namespace: ""
- Name: PlanningScene
- Planning Scene Topic: move_group/monitored_planning_scene
- Robot Description: robot_description
- Scene Geometry:
- Scene Alpha: 0.9
- Show Scene Geometry: true
- Voxel Coloring: Z-Axis
- Voxel Rendering: Occupied Voxels
- Scene Robot:
- Attached Body Color: 150; 50; 150
- Links: ~
- Robot Alpha: 1
- Show Robot Collision: false
- Show Robot Visual: true
- Value: true
- Enabled: true
- Global Options:
- Background Color: 48; 48; 48
- Default Light: true
- Fixed Frame: panda_link0
- Frame Rate: 30
- Name: root
- Tools:
- - Class: rviz/Interact
- Hide Inactive Objects: true
- - Class: rviz/MoveCamera
- - Class: rviz/Select
- - Class: rviz_visual_tools/KeyTool
- 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: panda_link0
- Yaw: -0.6232355833053589
- Saved: ~
-Window Geometry:
- Displays:
- collapsed: false
- Height: 848
- Help:
- collapsed: false
- Hide Left Dock: false
- Hide Right Dock: false
- QMainWindow State: 000000ff00000000fd0000000100000000000001f0000002f6fc0200000009fb000000100044006900730070006c006100790073010000003d000002af000000c900fffffffb0000000800480065006c00700000000342000000bb0000006e00fffffffb0000000a00560069006500770073000000010c000000a4000000a400fffffffb0000000c00430061006d00650072006100000002ff000001610000000000000000fb0000001e004d006f00740069006f006e00200050006c0061006e006e0069006e00670100000374000001890000000000000000fb00000044004d006f00740069006f006e0050006c0061006e006e0069006e00670020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000000000000000fb0000001c004d006f00740069006f006e0050006c0061006e006e0069006e006700000001ab000001880000000000000000fb000000280020002d0020005400720061006a006500630074006f0072007900200053006c00690064006500720000000000ffffffff0000004100fffffffb00000024005200760069007a00560069007300750061006c0054006f006f006c007300470075006901000002f2000000410000004100ffffff00000315000002f600000001000000020000000100000002fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
- RvizVisualToolsGui:
- collapsed: false
- Trajectory - Slider:
- collapsed: false
- Views:
- collapsed: false
- Width: 1291
- X: 449
- Y: 25
diff --git a/launch/ompl-chomp_planning_pipeline.launch.xml b/launch/ompl-chomp_planning_pipeline.launch.xml
deleted file mode 100644
index 178d2be..0000000
--- a/launch/ompl-chomp_planning_pipeline.launch.xml
+++ /dev/null
@@ -1,19 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/launch/ompl_planning_pipeline.launch.xml b/launch/ompl_planning_pipeline.launch.xml
deleted file mode 100644
index af9d56e..0000000
--- a/launch/ompl_planning_pipeline.launch.xml
+++ /dev/null
@@ -1,27 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/launch/panda_moveit_sensor_manager.launch.xml b/launch/panda_moveit_sensor_manager.launch.xml
deleted file mode 100644
index 5d02698..0000000
--- a/launch/panda_moveit_sensor_manager.launch.xml
+++ /dev/null
@@ -1,3 +0,0 @@
-
-
-
diff --git a/launch/pilz_industrial_motion_planner_planning_pipeline.launch.xml b/launch/pilz_industrial_motion_planner_planning_pipeline.launch.xml
deleted file mode 100644
index c7c4cf5..0000000
--- a/launch/pilz_industrial_motion_planner_planning_pipeline.launch.xml
+++ /dev/null
@@ -1,15 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/launch/planning_context.launch b/launch/planning_context.launch
deleted file mode 100644
index b591e1a..0000000
--- a/launch/planning_context.launch
+++ /dev/null
@@ -1,28 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/launch/planning_pipeline.launch.xml b/launch/planning_pipeline.launch.xml
deleted file mode 100644
index 250e743..0000000
--- a/launch/planning_pipeline.launch.xml
+++ /dev/null
@@ -1,11 +0,0 @@
-
-
-
-
-
-
-
-
-
-
diff --git a/launch/ros_control_moveit_controller_manager.launch.xml b/launch/ros_control_moveit_controller_manager.launch.xml
deleted file mode 100644
index 9ebc91c..0000000
--- a/launch/ros_control_moveit_controller_manager.launch.xml
+++ /dev/null
@@ -1,4 +0,0 @@
-
-
-
-
diff --git a/launch/ros_controllers.launch b/launch/ros_controllers.launch
deleted file mode 100644
index 47806e5..0000000
--- a/launch/ros_controllers.launch
+++ /dev/null
@@ -1,10 +0,0 @@
-
-
-
-
-
-
-
-
-
diff --git a/launch/run_benchmark_ompl.launch b/launch/run_benchmark_ompl.launch
deleted file mode 100644
index 4bbfb37..0000000
--- a/launch/run_benchmark_ompl.launch
+++ /dev/null
@@ -1,21 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/launch/run_benchmark_trajopt.launch b/launch/run_benchmark_trajopt.launch
deleted file mode 100644
index 7628416..0000000
--- a/launch/run_benchmark_trajopt.launch
+++ /dev/null
@@ -1,21 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/launch/sensor_manager.launch.xml b/launch/sensor_manager.launch.xml
deleted file mode 100644
index 61db9d9..0000000
--- a/launch/sensor_manager.launch.xml
+++ /dev/null
@@ -1,19 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/launch/setup_assistant.launch b/launch/setup_assistant.launch
deleted file mode 100644
index d647abe..0000000
--- a/launch/setup_assistant.launch
+++ /dev/null
@@ -1,16 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/launch/simple_moveit_controller_manager.launch.xml b/launch/simple_moveit_controller_manager.launch.xml
deleted file mode 100644
index 44e6d6c..0000000
--- a/launch/simple_moveit_controller_manager.launch.xml
+++ /dev/null
@@ -1,7 +0,0 @@
-
-
-
-
-
-
-
diff --git a/launch/stomp_planning_pipeline.launch.xml b/launch/stomp_planning_pipeline.launch.xml
deleted file mode 100644
index cbff8df..0000000
--- a/launch/stomp_planning_pipeline.launch.xml
+++ /dev/null
@@ -1,34 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/launch/trajectory_execution.launch.xml b/launch/trajectory_execution.launch.xml
deleted file mode 100644
index 20c3dfc..0000000
--- a/launch/trajectory_execution.launch.xml
+++ /dev/null
@@ -1,23 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/launch/trajopt_planning_pipeline.launch.xml b/launch/trajopt_planning_pipeline.launch.xml
deleted file mode 100644
index ec9ea9b..0000000
--- a/launch/trajopt_planning_pipeline.launch.xml
+++ /dev/null
@@ -1,32 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/launch/warehouse.launch b/launch/warehouse.launch
deleted file mode 100644
index 0712e67..0000000
--- a/launch/warehouse.launch
+++ /dev/null
@@ -1,15 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/launch/warehouse_settings.launch.xml b/launch/warehouse_settings.launch.xml
deleted file mode 100644
index e473b08..0000000
--- a/launch/warehouse_settings.launch.xml
+++ /dev/null
@@ -1,16 +0,0 @@
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
-
diff --git a/package.xml b/package.xml
index 4ed28fd..0d4a1f6 100644
--- a/package.xml
+++ b/package.xml
@@ -1,40 +1,43 @@
-
-
+
+
panda_moveit_config
0.8.1
An automatically generated package with all the configuration and launch files for using the panda with the MoveIt Motion Planning Framework
- MoveIt maintainer team
- MoveIt maintainer team
+ MoveIt maintainer team
+ MoveIt maintainer team
BSD
-
+
http://moveit.ros.org/
https://github.com/ros-planning/moveit/issues
https://github.com/ros-planning/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
+ ament_cmake
+
+ 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
- franka_description
-
+ franka_description
+
+
+ ament_cmake
+