diff --git a/motoman_csda10f_moveit_config/.setup_assistant b/motoman_csda10f_moveit_config/.setup_assistant new file mode 100644 index 00000000..d646c8ea --- /dev/null +++ b/motoman_csda10f_moveit_config/.setup_assistant @@ -0,0 +1,10 @@ +moveit_setup_assistant_config: + URDF: + package: motoman_csda10f_support + relative_path: urdf/csda10f.xacro + SRDF: + relative_path: config/motoman_csda10f.srdf + CONFIG: + author_name: Amrith Ganesh + author_email: amrith1007@gmail.com + generated_timestamp: 1518465357 \ No newline at end of file diff --git a/motoman_csda10f_moveit_config/CMakeLists.txt b/motoman_csda10f_moveit_config/CMakeLists.txt new file mode 100644 index 00000000..4e801e21 --- /dev/null +++ b/motoman_csda10f_moveit_config/CMakeLists.txt @@ -0,0 +1,10 @@ +cmake_minimum_required(VERSION 2.8.3) +project(motoman_csda10f_moveit_config) + +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/motoman_csda10f_moveit_config/config/controllers.yaml b/motoman_csda10f_moveit_config/config/controllers.yaml new file mode 100644 index 00000000..4d88c9bd --- /dev/null +++ b/motoman_csda10f_moveit_config/config/controllers.yaml @@ -0,0 +1,48 @@ +controller_list: + - name: '' + action_ns: joint_trajectory_action + type: FollowJointTrajectory + joints: [arm_left_joint_1_s, + arm_left_joint_2_l, + arm_left_joint_3_e, + arm_left_joint_4_u, + arm_left_joint_5_r, + arm_left_joint_6_b, + arm_left_joint_7_t, + arm_right_joint_1_s, + arm_right_joint_2_l, + arm_right_joint_3_e, + arm_right_joint_4_u, + arm_right_joint_5_r, + arm_right_joint_6_b, + arm_right_joint_7_t, + torso_joint_b1, + torso_joint_b2] + - name: csda10f/csda10f_r1_controller + action_ns: joint_trajectory_action + type: FollowJointTrajectory + joints: [arm_left_joint_1_s, + arm_left_joint_2_l, + arm_left_joint_3_e, + arm_left_joint_4_u, + arm_left_joint_5_r, + arm_left_joint_6_b, + arm_left_joint_7_t] + - name: csda10f/csda10f_b1_controller + action_ns: joint_trajectory_action + type: FollowJointTrajectory + joints: [torso_joint_b1] + - name: csda10f/csda10f_b2_controller + action_ns: joint_trajectory_action + type: FollowJointTrajectory + joints: [torso_joint_b2] + - name: csda10f/csda10f_r2_controller + action_ns: joint_trajectory_action + type: FollowJointTrajectory + joints: [arm_right_joint_1_s, + arm_right_joint_2_l, + arm_right_joint_3_e, + arm_right_joint_4_u, + arm_right_joint_5_r, + arm_right_joint_6_b, + arm_right_joint_7_t] \ No newline at end of file diff --git a/motoman_csda10f_moveit_config/config/fake_controllers.yaml b/motoman_csda10f_moveit_config/config/fake_controllers.yaml new file mode 100644 index 00000000..1cf774aa --- /dev/null +++ b/motoman_csda10f_moveit_config/config/fake_controllers.yaml @@ -0,0 +1,55 @@ +controller_list: + - name: fake_arm_left_controller + joints: + - arm_left_joint_1_s + - arm_left_joint_2_l + - arm_left_joint_3_e + - arm_left_joint_4_u + - arm_left_joint_5_r + - arm_left_joint_6_b + - arm_left_joint_7_t + - name: fake_arm_right_controller + joints: + - arm_right_joint_1_s + - arm_right_joint_2_l + - arm_right_joint_3_e + - arm_right_joint_4_u + - arm_right_joint_5_r + - arm_right_joint_6_b + - arm_right_joint_7_t + - name: fake_torso_controller + joints: + - torso_joint_b1 + - name: fake_arms_controller + joints: + - arm_left_joint_1_s + - arm_left_joint_2_l + - arm_left_joint_3_e + - arm_left_joint_4_u + - arm_left_joint_5_r + - arm_left_joint_6_b + - arm_left_joint_7_t + - arm_right_joint_1_s + - arm_right_joint_2_l + - arm_right_joint_3_e + - arm_right_joint_4_u + - arm_right_joint_5_r + - arm_right_joint_6_b + - arm_right_joint_7_t + - name: fake_csda10f_controller + joints: + - torso_joint_b1 + - arm_left_joint_1_s + - arm_left_joint_2_l + - arm_left_joint_3_e + - arm_left_joint_4_u + - arm_left_joint_5_r + - arm_left_joint_6_b + - arm_left_joint_7_t + - arm_right_joint_1_s + - arm_right_joint_2_l + - arm_right_joint_3_e + - arm_right_joint_4_u + - arm_right_joint_5_r + - arm_right_joint_6_b + - arm_right_joint_7_t \ No newline at end of file diff --git a/motoman_csda10f_moveit_config/config/joint_limits.yaml b/motoman_csda10f_moveit_config/config/joint_limits.yaml new file mode 100644 index 00000000..ecc6523d --- /dev/null +++ b/motoman_csda10f_moveit_config/config/joint_limits.yaml @@ -0,0 +1,84 @@ +# joint_limits.yaml allows the dynamics properties specified in the URDF to be overwritten or augmented as needed +# 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: + arm_left_joint_1_s: + has_velocity_limits: true + max_velocity: 2.95 + has_acceleration_limits: false + max_acceleration: 0 + arm_left_joint_2_l: + has_velocity_limits: true + max_velocity: 2.95 + has_acceleration_limits: false + max_acceleration: 0 + arm_left_joint_3_e: + has_velocity_limits: true + max_velocity: 2.95 + has_acceleration_limits: false + max_acceleration: 0 + arm_left_joint_4_u: + has_velocity_limits: true + max_velocity: 2.95 + has_acceleration_limits: false + max_acceleration: 0 + arm_left_joint_5_r: + has_velocity_limits: true + max_velocity: 3.48 + has_acceleration_limits: false + max_acceleration: 0 + arm_left_joint_6_b: + has_velocity_limits: true + max_velocity: 3.48 + has_acceleration_limits: false + max_acceleration: 0 + arm_left_joint_7_t: + has_velocity_limits: true + max_velocity: 6.97 + has_acceleration_limits: false + max_acceleration: 0 + arm_right_joint_1_s: + has_velocity_limits: true + max_velocity: 2.95 + has_acceleration_limits: false + max_acceleration: 0 + arm_right_joint_2_l: + has_velocity_limits: true + max_velocity: 2.95 + has_acceleration_limits: false + max_acceleration: 0 + arm_right_joint_3_e: + has_velocity_limits: true + max_velocity: 2.95 + has_acceleration_limits: false + max_acceleration: 0 + arm_right_joint_4_u: + has_velocity_limits: true + max_velocity: 2.95 + has_acceleration_limits: false + max_acceleration: 0 + arm_right_joint_5_r: + has_velocity_limits: true + max_velocity: 3.48 + has_acceleration_limits: false + max_acceleration: 0 + arm_right_joint_6_b: + has_velocity_limits: true + max_velocity: 3.48 + has_acceleration_limits: false + max_acceleration: 0 + arm_right_joint_7_t: + has_velocity_limits: true + max_velocity: 6.97 + has_acceleration_limits: false + max_acceleration: 0 + torso_joint_b1: + has_velocity_limits: true + max_velocity: 2.26 + has_acceleration_limits: false + max_acceleration: 0 + torso_joint_b2: + has_velocity_limits: true + max_velocity: 2.26 + has_acceleration_limits: false + max_acceleration: 0 \ No newline at end of file diff --git a/motoman_csda10f_moveit_config/config/kinematics.yaml b/motoman_csda10f_moveit_config/config/kinematics.yaml new file mode 100644 index 00000000..5f81e659 --- /dev/null +++ b/motoman_csda10f_moveit_config/config/kinematics.yaml @@ -0,0 +1,25 @@ +arm_left: + kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin + kinematics_solver_search_resolution: 0.005 + kinematics_solver_timeout: 0.005 + kinematics_solver_attempts: 3 +arm_right: + kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin + kinematics_solver_search_resolution: 0.005 + kinematics_solver_timeout: 0.005 + kinematics_solver_attempts: 3 +torso: + kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin + kinematics_solver_search_resolution: 0.005 + kinematics_solver_timeout: 0.005 + kinematics_solver_attempts: 3 +arms: + kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin + kinematics_solver_search_resolution: 0.005 + kinematics_solver_timeout: 0.005 + kinematics_solver_attempts: 5 +csda10f: + kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin + kinematics_solver_search_resolution: 0.005 + kinematics_solver_timeout: 0.005 + kinematics_solver_attempts: 10 \ No newline at end of file diff --git a/motoman_csda10f_moveit_config/config/motoman_csda10f.srdf b/motoman_csda10f_moveit_config/config/motoman_csda10f.srdf new file mode 100644 index 00000000..23d222af --- /dev/null +++ b/motoman_csda10f_moveit_config/config/motoman_csda10f.srdf @@ -0,0 +1,106 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/motoman_csda10f_moveit_config/config/ompl_planning.yaml b/motoman_csda10f_moveit_config/config/ompl_planning.yaml new file mode 100644 index 00000000..048e9b96 --- /dev/null +++ b/motoman_csda10f_moveit_config/config/ompl_planning.yaml @@ -0,0 +1,257 @@ +planner_configs: + SBLkConfigDefault: + type: geometric::SBL + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + 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 + 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 + 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 + 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 + 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 + 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 + RRTConnectkConfigDefault: + type: geometric::RRTConnect + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + 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 + 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 + 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 + 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() + PRMkConfigDefault: + type: geometric::PRM + max_nearest_neighbors: 10 # use k nearest neighbors. default: 10 + PRMstarkConfigDefault: + type: geometric::PRMstar + 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 + 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 + 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 + 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 + PDSTkConfigDefault: + type: geometric::PDST + 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 + 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 + 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 + init_temperature: 100 # initial temperature. default: 100 + 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 + 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 + BiESTkConfigDefault: + type: geometric::BiEST + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + 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 + LazyPRMkConfigDefault: + type: geometric::LazyPRM + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + LazyPRMstarkConfigDefault: + type: geometric::LazyPRMstar + 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 + 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 +arm_left: + planner_configs: + - SBLkConfigDefault + - ESTkConfigDefault + - LBKPIECEkConfigDefault + - BKPIECEkConfigDefault + - KPIECEkConfigDefault + - RRTkConfigDefault + - RRTConnectkConfigDefault + - RRTstarkConfigDefault + - TRRTkConfigDefault + - PRMkConfigDefault + - PRMstarkConfigDefault + - FMTkConfigDefault + - BFMTkConfigDefault + - PDSTkConfigDefault + - STRIDEkConfigDefault + - BiTRRTkConfigDefault + - LBTRRTkConfigDefault + - BiESTkConfigDefault + - ProjESTkConfigDefault + - LazyPRMkConfigDefault + - LazyPRMstarkConfigDefault + - SPARSkConfigDefault + - SPARStwokConfigDefault + projection_evaluator: joints(arm_left_joint_1_s,arm_left_joint_2_l) + longest_valid_segment_fraction: 0.005 +arm_right: + planner_configs: + - SBLkConfigDefault + - ESTkConfigDefault + - LBKPIECEkConfigDefault + - BKPIECEkConfigDefault + - KPIECEkConfigDefault + - RRTkConfigDefault + - RRTConnectkConfigDefault + - RRTstarkConfigDefault + - TRRTkConfigDefault + - PRMkConfigDefault + - PRMstarkConfigDefault + - FMTkConfigDefault + - BFMTkConfigDefault + - PDSTkConfigDefault + - STRIDEkConfigDefault + - BiTRRTkConfigDefault + - LBTRRTkConfigDefault + - BiESTkConfigDefault + - ProjESTkConfigDefault + - LazyPRMkConfigDefault + - LazyPRMstarkConfigDefault + - SPARSkConfigDefault + - SPARStwokConfigDefault + projection_evaluator: joints(arm_right_joint_1_s,arm_right_joint_2_l) + longest_valid_segment_fraction: 0.005 +torso: + planner_configs: + - SBLkConfigDefault + - ESTkConfigDefault + - LBKPIECEkConfigDefault + - BKPIECEkConfigDefault + - KPIECEkConfigDefault + - RRTkConfigDefault + - RRTConnectkConfigDefault + - RRTstarkConfigDefault + - TRRTkConfigDefault + - PRMkConfigDefault + - PRMstarkConfigDefault + - FMTkConfigDefault + - BFMTkConfigDefault + - PDSTkConfigDefault + - STRIDEkConfigDefault + - BiTRRTkConfigDefault + - LBTRRTkConfigDefault + - BiESTkConfigDefault + - ProjESTkConfigDefault + - LazyPRMkConfigDefault + - LazyPRMstarkConfigDefault + - SPARSkConfigDefault + - SPARStwokConfigDefault + projection_evaluator: joints(torso_joint_b1,torso_joint_b2) + longest_valid_segment_fraction: 0.005 +arms: + planner_configs: + - SBLkConfigDefault + - ESTkConfigDefault + - LBKPIECEkConfigDefault + - BKPIECEkConfigDefault + - KPIECEkConfigDefault + - RRTkConfigDefault + - RRTConnectkConfigDefault + - RRTstarkConfigDefault + - TRRTkConfigDefault + - PRMkConfigDefault + - PRMstarkConfigDefault + - FMTkConfigDefault + - BFMTkConfigDefault + - PDSTkConfigDefault + - STRIDEkConfigDefault + - BiTRRTkConfigDefault + - LBTRRTkConfigDefault + - BiESTkConfigDefault + - ProjESTkConfigDefault + - LazyPRMkConfigDefault + - LazyPRMstarkConfigDefault + - SPARSkConfigDefault + - SPARStwokConfigDefault + projection_evaluator: joints(arm_left_joint_1_s,arm_left_joint_2_l) + longest_valid_segment_fraction: 0.005 +csda10f: + planner_configs: + - SBLkConfigDefault + - ESTkConfigDefault + - LBKPIECEkConfigDefault + - BKPIECEkConfigDefault + - KPIECEkConfigDefault + - RRTkConfigDefault + - RRTConnectkConfigDefault + - RRTstarkConfigDefault + - TRRTkConfigDefault + - PRMkConfigDefault + - PRMstarkConfigDefault + - FMTkConfigDefault + - BFMTkConfigDefault + - PDSTkConfigDefault + - STRIDEkConfigDefault + - BiTRRTkConfigDefault + - LBTRRTkConfigDefault + - BiESTkConfigDefault + - ProjESTkConfigDefault + - LazyPRMkConfigDefault + - LazyPRMstarkConfigDefault + - SPARSkConfigDefault + - SPARStwokConfigDefault + projection_evaluator: joints(torso_joint_b1,arm_left_joint_1_s) + longest_valid_segment_fraction: 0.005 \ No newline at end of file diff --git a/motoman_csda10f_moveit_config/launch/default_warehouse_db.launch b/motoman_csda10f_moveit_config/launch/default_warehouse_db.launch new file mode 100644 index 00000000..7a9a6312 --- /dev/null +++ b/motoman_csda10f_moveit_config/launch/default_warehouse_db.launch @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + + diff --git a/motoman_csda10f_moveit_config/launch/demo.launch b/motoman_csda10f_moveit_config/launch/demo.launch new file mode 100644 index 00000000..13a3fed9 --- /dev/null +++ b/motoman_csda10f_moveit_config/launch/demo.launch @@ -0,0 +1,57 @@ + + + + + + + + + + + + + + + + + + + + + + + + + [/move_group/fake_controller_joint_states] + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/motoman_csda10f_moveit_config/launch/fake_moveit_controller_manager.launch.xml b/motoman_csda10f_moveit_config/launch/fake_moveit_controller_manager.launch.xml new file mode 100644 index 00000000..02b5fe6c --- /dev/null +++ b/motoman_csda10f_moveit_config/launch/fake_moveit_controller_manager.launch.xml @@ -0,0 +1,9 @@ + + + + + + + + + diff --git a/motoman_csda10f_moveit_config/launch/joystick_control.launch b/motoman_csda10f_moveit_config/launch/joystick_control.launch new file mode 100644 index 00000000..f7417352 --- /dev/null +++ b/motoman_csda10f_moveit_config/launch/joystick_control.launch @@ -0,0 +1,17 @@ + + + + + + + + + + + + + + + + + diff --git a/motoman_csda10f_moveit_config/launch/motoman_csda10f_moveit_controller_manager.launch.xml b/motoman_csda10f_moveit_config/launch/motoman_csda10f_moveit_controller_manager.launch.xml new file mode 100644 index 00000000..452a8c95 --- /dev/null +++ b/motoman_csda10f_moveit_config/launch/motoman_csda10f_moveit_controller_manager.launch.xml @@ -0,0 +1,9 @@ + + + + + + + + + diff --git a/motoman_csda10f_moveit_config/launch/motoman_csda10f_moveit_sensor_manager.launch.xml b/motoman_csda10f_moveit_config/launch/motoman_csda10f_moveit_sensor_manager.launch.xml new file mode 100644 index 00000000..5d02698d --- /dev/null +++ b/motoman_csda10f_moveit_config/launch/motoman_csda10f_moveit_sensor_manager.launch.xml @@ -0,0 +1,3 @@ + + + diff --git a/motoman_csda10f_moveit_config/launch/move_group.launch b/motoman_csda10f_moveit_config/launch/move_group.launch new file mode 100644 index 00000000..a608d022 --- /dev/null +++ b/motoman_csda10f_moveit_config/launch/move_group.launch @@ -0,0 +1,72 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/motoman_csda10f_moveit_config/launch/moveit.rviz b/motoman_csda10f_moveit_config/launch/moveit.rviz new file mode 100644 index 00000000..0877e1e7 --- /dev/null +++ b/motoman_csda10f_moveit_config/launch/moveit.rviz @@ -0,0 +1,689 @@ +Panels: + - Class: rviz/Displays + Help Height: 84 + Name: Displays + Property Tree Widget: + Expanded: + - /MotionPlanning1 + Splitter Ratio: 0.74256 + Tree Height: 664 + - 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 + MoveIt_Goal_Tolerance: 0 + MoveIt_Planning_Time: 5 + MoveIt_Use_Constraint_Aware_IK: true + MoveIt_Warehouse_Host: 127.0.0.1 + MoveIt_Warehouse_Port: 33829 + Name: MotionPlanning + Planned Path: + Links: + base_bellow_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + base_footprint: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + bl_caster_l_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + bl_caster_r_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + bl_caster_rotation_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + br_caster_l_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + br_caster_r_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + br_caster_rotation_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + double_stereo_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fl_caster_l_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fl_caster_r_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fl_caster_rotation_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fr_caster_l_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fr_caster_r_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fr_caster_rotation_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_mount_kinect_ir_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_mount_kinect_rgb_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_mount_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_mount_prosilica_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_pan_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_plate_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_tilt_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_elbow_flex_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_forearm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_forearm_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_l_finger_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_l_finger_tip_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_motor_accelerometer_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_palm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_r_finger_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_r_finger_tip_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_shoulder_lift_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_shoulder_pan_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_upper_arm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_upper_arm_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_wrist_flex_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_wrist_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + laser_tilt_mount_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_elbow_flex_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_forearm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_forearm_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_l_finger_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_l_finger_tip_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_motor_accelerometer_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_palm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_r_finger_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_r_finger_tip_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_shoulder_lift_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_shoulder_pan_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_upper_arm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_upper_arm_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_wrist_flex_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_wrist_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + sensor_mount_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + torso_lift_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + 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 + Planning Group: left_arm + 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 + Scene Color: 50; 230; 50 + Scene Display Time: 0.2 + Show Scene Geometry: true + Voxel Coloring: Z-Axis + Voxel Rendering: Occupied Voxels + Scene Robot: + Attached Body Color: 150; 50; 150 + Links: + base_bellow_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + base_footprint: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + bl_caster_l_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + bl_caster_r_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + bl_caster_rotation_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + br_caster_l_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + br_caster_r_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + br_caster_rotation_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + double_stereo_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fl_caster_l_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fl_caster_r_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fl_caster_rotation_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fr_caster_l_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fr_caster_r_wheel_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + fr_caster_rotation_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_mount_kinect_ir_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_mount_kinect_rgb_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_mount_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_mount_prosilica_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_pan_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_plate_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + head_tilt_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_elbow_flex_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_forearm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_forearm_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_l_finger_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_l_finger_tip_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_motor_accelerometer_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_palm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_r_finger_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_gripper_r_finger_tip_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_shoulder_lift_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_shoulder_pan_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_upper_arm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_upper_arm_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_wrist_flex_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + l_wrist_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + laser_tilt_mount_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_elbow_flex_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_forearm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_forearm_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_l_finger_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_l_finger_tip_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_motor_accelerometer_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_palm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_r_finger_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_gripper_r_finger_tip_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_shoulder_lift_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_shoulder_pan_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_upper_arm_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_upper_arm_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_wrist_flex_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + r_wrist_roll_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + sensor_mount_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + torso_lift_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + Robot Alpha: 0.5 + Show Scene Robot: true + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: /base_link + Name: root + Tools: + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/MoveCamera + - Class: rviz/Select + Value: true + Views: + Current: + Class: rviz/XYOrbit + Distance: 2.9965 + Focal Point: + X: 0.113567 + Y: 0.10592 + Z: 2.23518e-07 + Name: Current View + Near Clip Distance: 0.01 + Pitch: 0.509797 + Target Frame: /base_link + Value: XYOrbit (rviz) + Yaw: 5.65995 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 1337 + Help: + collapsed: false + Hide Left Dock: false + Hide Right Dock: false + Motion Planning: + collapsed: false + QMainWindow State: 000000ff00000000fd0000000100000000000002a2000004bcfc0200000005fb000000100044006900730070006c00610079007301000000410000032d000000dd00fffffffb0000000800480065006c00700000000342000000bb0000007600fffffffb0000000a0056006900650077007300000003b0000000b0000000b000fffffffb0000000c00430061006d00650072006100000002ff000001610000000000000000fb0000001e004d006f00740069006f006e00200050006c0061006e006e0069006e00670100000374000001890000017400ffffff0000047a000004bc00000001000000020000000100000002fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Views: + collapsed: false + Width: 1828 + X: 459 + Y: -243 diff --git a/motoman_csda10f_moveit_config/launch/moveit_planning_execution.launch b/motoman_csda10f_moveit_config/launch/moveit_planning_execution.launch new file mode 100644 index 00000000..7c9afd7a --- /dev/null +++ b/motoman_csda10f_moveit_config/launch/moveit_planning_execution.launch @@ -0,0 +1,56 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/motoman_csda10f_moveit_config/launch/moveit_rviz.launch b/motoman_csda10f_moveit_config/launch/moveit_rviz.launch new file mode 100644 index 00000000..4b84dfed --- /dev/null +++ b/motoman_csda10f_moveit_config/launch/moveit_rviz.launch @@ -0,0 +1,16 @@ + + + + + + + + + + + + + + + diff --git a/motoman_csda10f_moveit_config/launch/ompl_planning_pipeline.launch.xml b/motoman_csda10f_moveit_config/launch/ompl_planning_pipeline.launch.xml new file mode 100644 index 00000000..53c97f3d --- /dev/null +++ b/motoman_csda10f_moveit_config/launch/ompl_planning_pipeline.launch.xml @@ -0,0 +1,22 @@ + + + + + + + + + + + + + + + + + diff --git a/motoman_csda10f_moveit_config/launch/planning_context.launch b/motoman_csda10f_moveit_config/launch/planning_context.launch new file mode 100644 index 00000000..fb615d5d --- /dev/null +++ b/motoman_csda10f_moveit_config/launch/planning_context.launch @@ -0,0 +1,24 @@ + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/motoman_csda10f_moveit_config/launch/planning_pipeline.launch.xml b/motoman_csda10f_moveit_config/launch/planning_pipeline.launch.xml new file mode 100644 index 00000000..cfe5062a --- /dev/null +++ b/motoman_csda10f_moveit_config/launch/planning_pipeline.launch.xml @@ -0,0 +1,10 @@ + + + + + + + + + diff --git a/motoman_csda10f_moveit_config/launch/run_benchmark_ompl.launch b/motoman_csda10f_moveit_config/launch/run_benchmark_ompl.launch new file mode 100644 index 00000000..74cbaf17 --- /dev/null +++ b/motoman_csda10f_moveit_config/launch/run_benchmark_ompl.launch @@ -0,0 +1,22 @@ + + + + + + + + + + + + + + + + + + + + + + diff --git a/motoman_csda10f_moveit_config/launch/sensor_manager.launch.xml b/motoman_csda10f_moveit_config/launch/sensor_manager.launch.xml new file mode 100644 index 00000000..1bd9ae25 --- /dev/null +++ b/motoman_csda10f_moveit_config/launch/sensor_manager.launch.xml @@ -0,0 +1,14 @@ + + + + + + + + + + + + + + diff --git a/motoman_csda10f_moveit_config/launch/setup_assistant.launch b/motoman_csda10f_moveit_config/launch/setup_assistant.launch new file mode 100644 index 00000000..88e2b072 --- /dev/null +++ b/motoman_csda10f_moveit_config/launch/setup_assistant.launch @@ -0,0 +1,15 @@ + + + + + + + + + + + + diff --git a/motoman_csda10f_moveit_config/launch/trajectory_execution.launch.xml b/motoman_csda10f_moveit_config/launch/trajectory_execution.launch.xml new file mode 100644 index 00000000..2cf33b1c --- /dev/null +++ b/motoman_csda10f_moveit_config/launch/trajectory_execution.launch.xml @@ -0,0 +1,20 @@ + + + + + + + + + + + + + + + + + + + + diff --git a/motoman_csda10f_moveit_config/launch/warehouse.launch b/motoman_csda10f_moveit_config/launch/warehouse.launch new file mode 100644 index 00000000..ea6cd022 --- /dev/null +++ b/motoman_csda10f_moveit_config/launch/warehouse.launch @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + + diff --git a/motoman_csda10f_moveit_config/launch/warehouse_settings.launch.xml b/motoman_csda10f_moveit_config/launch/warehouse_settings.launch.xml new file mode 100644 index 00000000..967e0ff4 --- /dev/null +++ b/motoman_csda10f_moveit_config/launch/warehouse_settings.launch.xml @@ -0,0 +1,16 @@ + + + + + + + + + + + + + + + + diff --git a/motoman_csda10f_moveit_config/package.xml b/motoman_csda10f_moveit_config/package.xml new file mode 100644 index 00000000..f0de9889 --- /dev/null +++ b/motoman_csda10f_moveit_config/package.xml @@ -0,0 +1,36 @@ + + + + motoman_csda10f_moveit_config + 0.2.0 + + Package with all the configuration and launch files for using the motoman_csda10f with the MoveIt! Motion Planning Framework, and ready to work with FS100 controller. + + Amrith Ganesh + Amrith Ganesh + Daniel Ordonez + + BSD + + http://wiki.ros.org/motoman_sda10f_moveit_config + https://github.com/ros-industrial/motoman/issues + https://github.com/ros-industrial/motoman + + catkin + + moveit_ros_move_group + moveit_fake_controller_manager + moveit_kinematics + moveit_planners_ompl + moveit_ros_visualization + joint_state_publisher + robot_state_publisher + xacro + + + motoman_csda10f_support + + + + + diff --git a/motoman_csda10f_support/CMakeLists.txt b/motoman_csda10f_support/CMakeLists.txt new file mode 100644 index 00000000..d6881c1b --- /dev/null +++ b/motoman_csda10f_support/CMakeLists.txt @@ -0,0 +1,11 @@ + +cmake_minimum_required(VERSION 2.8.3) + +project(motoman_csda10f_support) + +find_package(catkin REQUIRED) + +catkin_package() + +install(DIRECTORY config launch meshes urdf + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) diff --git a/motoman_csda10f_support/config/csda10f_motion_interface.yaml b/motoman_csda10f_support/config/csda10f_motion_interface.yaml new file mode 100644 index 00000000..c2467397 --- /dev/null +++ b/motoman_csda10f_support/config/csda10f_motion_interface.yaml @@ -0,0 +1,18 @@ +# Ordering from 0 to 4 is required due to FS100 controller configuration, but it can be that ordering starting from 1 works for you. +topic_list: + - name: csda10f_r1_controller + ns: csda10f + group: 0 + joints: ['arm_left_joint_1_s','arm_left_joint_2_l','arm_left_joint_3_e','arm_left_joint_4_u','arm_left_joint_5_r','arm_left_joint_6_b','arm_left_joint_7_t'] + - name: csda10f_r2_controller + ns: csda10f + group: 1 + joints: ['arm_right_joint_1_s','arm_right_joint_2_l','arm_right_joint_3_e','arm_right_joint_4_u','arm_right_joint_5_r','arm_right_joint_6_b','arm_right_joint_7_t'] + - name: csda10f_b1_controller + ns: csda10f + group: 2 + joints: ['torso_joint_b1'] + - name: csda10f_b2_controller + ns: csda10f + group: 3 + joints: ['torso_joint_b2'] diff --git a/motoman_csda10f_support/config/joint_names_csda10f.yaml b/motoman_csda10f_support/config/joint_names_csda10f.yaml new file mode 100644 index 00000000..bdd124f0 --- /dev/null +++ b/motoman_csda10f_support/config/joint_names_csda10f.yaml @@ -0,0 +1,5 @@ +# The order of this list should match that expected by your robot's socket interface. Typically Base -> Tip. +controller_joint_names: ['arm_left_joint_1_s','arm_left_joint_2_l','arm_left_joint_3_e' +,'arm_left_joint_4_u','arm_left_joint_5_r','arm_left_joint_6_b','arm_left_joint_7_t', +'arm_right_joint_1_s','arm_right_joint_2_l','arm_right_joint_3_e','arm_right_joint_4_u', +'arm_right_joint_5_r','arm_right_joint_6_b','arm_right_joint_7_t','torso_joint_b1','torso_joint_b2'] diff --git a/motoman_csda10f_support/launch/load_csda10f.launch b/motoman_csda10f_support/launch/load_csda10f.launch new file mode 100644 index 00000000..080ed2a7 --- /dev/null +++ b/motoman_csda10f_support/launch/load_csda10f.launch @@ -0,0 +1,4 @@ + + + + diff --git a/motoman_csda10f_support/launch/robot_interface_streaming_csda10f.launch b/motoman_csda10f_support/launch/robot_interface_streaming_csda10f.launch new file mode 100644 index 00000000..33d26ab9 --- /dev/null +++ b/motoman_csda10f_support/launch/robot_interface_streaming_csda10f.launch @@ -0,0 +1,21 @@ + + + + + + + + + + + + + diff --git a/motoman_csda10f_support/launch/robot_state_visualize_csda10f.launch b/motoman_csda10f_support/launch/robot_state_visualize_csda10f.launch new file mode 100644 index 00000000..80c377a7 --- /dev/null +++ b/motoman_csda10f_support/launch/robot_state_visualize_csda10f.launch @@ -0,0 +1,33 @@ + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/motoman_csda10f_support/launch/test_csda10f.launch b/motoman_csda10f_support/launch/test_csda10f.launch new file mode 100644 index 00000000..efc3f452 --- /dev/null +++ b/motoman_csda10f_support/launch/test_csda10f.launch @@ -0,0 +1,12 @@ + + + + + + + + + + + + diff --git a/motoman_csda10f_support/meshes/csda10f/collision/csda_axis_b.stl b/motoman_csda10f_support/meshes/csda10f/collision/csda_axis_b.stl new file mode 100644 index 00000000..66c2210a Binary files /dev/null and b/motoman_csda10f_support/meshes/csda10f/collision/csda_axis_b.stl differ diff --git a/motoman_csda10f_support/meshes/csda10f/collision/csda_axis_b1.stl b/motoman_csda10f_support/meshes/csda10f/collision/csda_axis_b1.stl new file mode 100644 index 00000000..258342dc Binary files /dev/null and b/motoman_csda10f_support/meshes/csda10f/collision/csda_axis_b1.stl differ diff --git a/motoman_csda10f_support/meshes/csda10f/collision/csda_axis_e.stl b/motoman_csda10f_support/meshes/csda10f/collision/csda_axis_e.stl new file mode 100644 index 00000000..824f7c3a Binary files /dev/null and b/motoman_csda10f_support/meshes/csda10f/collision/csda_axis_e.stl differ diff --git a/motoman_csda10f_support/meshes/csda10f/collision/csda_axis_l.stl b/motoman_csda10f_support/meshes/csda10f/collision/csda_axis_l.stl new file mode 100644 index 00000000..227da378 Binary files /dev/null and b/motoman_csda10f_support/meshes/csda10f/collision/csda_axis_l.stl differ diff --git a/motoman_csda10f_support/meshes/csda10f/collision/csda_axis_r.stl b/motoman_csda10f_support/meshes/csda10f/collision/csda_axis_r.stl new file mode 100644 index 00000000..e51561a0 Binary files /dev/null and b/motoman_csda10f_support/meshes/csda10f/collision/csda_axis_r.stl differ diff --git a/motoman_csda10f_support/meshes/csda10f/collision/csda_axis_s.stl b/motoman_csda10f_support/meshes/csda10f/collision/csda_axis_s.stl new file mode 100644 index 00000000..810f7e68 Binary files /dev/null and b/motoman_csda10f_support/meshes/csda10f/collision/csda_axis_s.stl differ diff --git a/motoman_csda10f_support/meshes/csda10f/collision/csda_axis_t.stl b/motoman_csda10f_support/meshes/csda10f/collision/csda_axis_t.stl new file mode 100644 index 00000000..1fdc4e22 Binary files /dev/null and b/motoman_csda10f_support/meshes/csda10f/collision/csda_axis_t.stl differ diff --git a/motoman_csda10f_support/meshes/csda10f/collision/csda_axis_u.stl b/motoman_csda10f_support/meshes/csda10f/collision/csda_axis_u.stl new file mode 100644 index 00000000..f53d3c25 Binary files /dev/null and b/motoman_csda10f_support/meshes/csda10f/collision/csda_axis_u.stl differ diff --git a/motoman_csda10f_support/meshes/csda10f/collision/csda_base.stl b/motoman_csda10f_support/meshes/csda10f/collision/csda_base.stl new file mode 100644 index 00000000..053167c8 Binary files /dev/null and b/motoman_csda10f_support/meshes/csda10f/collision/csda_base.stl differ diff --git a/motoman_csda10f_support/meshes/csda10f/visual/csda_axis_b.STL b/motoman_csda10f_support/meshes/csda10f/visual/csda_axis_b.STL new file mode 100644 index 00000000..801ad74e Binary files /dev/null and b/motoman_csda10f_support/meshes/csda10f/visual/csda_axis_b.STL differ diff --git a/motoman_csda10f_support/meshes/csda10f/visual/csda_axis_b1.STL b/motoman_csda10f_support/meshes/csda10f/visual/csda_axis_b1.STL new file mode 100644 index 00000000..19d98c8b Binary files /dev/null and b/motoman_csda10f_support/meshes/csda10f/visual/csda_axis_b1.STL differ diff --git a/motoman_csda10f_support/meshes/csda10f/visual/csda_axis_e.STL b/motoman_csda10f_support/meshes/csda10f/visual/csda_axis_e.STL new file mode 100644 index 00000000..fba2b520 Binary files /dev/null and b/motoman_csda10f_support/meshes/csda10f/visual/csda_axis_e.STL differ diff --git a/motoman_csda10f_support/meshes/csda10f/visual/csda_axis_l.STL b/motoman_csda10f_support/meshes/csda10f/visual/csda_axis_l.STL new file mode 100644 index 00000000..33d0df13 Binary files /dev/null and b/motoman_csda10f_support/meshes/csda10f/visual/csda_axis_l.STL differ diff --git a/motoman_csda10f_support/meshes/csda10f/visual/csda_axis_r.STL b/motoman_csda10f_support/meshes/csda10f/visual/csda_axis_r.STL new file mode 100644 index 00000000..2fe6a2b7 Binary files /dev/null and b/motoman_csda10f_support/meshes/csda10f/visual/csda_axis_r.STL differ diff --git a/motoman_csda10f_support/meshes/csda10f/visual/csda_axis_s.STL b/motoman_csda10f_support/meshes/csda10f/visual/csda_axis_s.STL new file mode 100644 index 00000000..0fc37df0 Binary files /dev/null and b/motoman_csda10f_support/meshes/csda10f/visual/csda_axis_s.STL differ diff --git a/motoman_csda10f_support/meshes/csda10f/visual/csda_axis_t.STL b/motoman_csda10f_support/meshes/csda10f/visual/csda_axis_t.STL new file mode 100644 index 00000000..b9ebbf8e Binary files /dev/null and b/motoman_csda10f_support/meshes/csda10f/visual/csda_axis_t.STL differ diff --git a/motoman_csda10f_support/meshes/csda10f/visual/csda_axis_u.STL b/motoman_csda10f_support/meshes/csda10f/visual/csda_axis_u.STL new file mode 100644 index 00000000..d00d8fe2 Binary files /dev/null and b/motoman_csda10f_support/meshes/csda10f/visual/csda_axis_u.STL differ diff --git a/motoman_csda10f_support/meshes/csda10f/visual/csda_base.STL b/motoman_csda10f_support/meshes/csda10f/visual/csda_base.STL new file mode 100644 index 00000000..b8ab0af3 Binary files /dev/null and b/motoman_csda10f_support/meshes/csda10f/visual/csda_base.STL differ diff --git a/motoman_csda10f_support/package.xml b/motoman_csda10f_support/package.xml new file mode 100644 index 00000000..b74e6ae9 --- /dev/null +++ b/motoman_csda10f_support/package.xml @@ -0,0 +1,52 @@ + + + motoman_csda10f_support + 0.3.5 + +

+ ROS Industrial support for the Motoman csda10f (and variants). +

+

+ This package contains configuration data, 3D models and launch files + for Motoman csda10f manipulators. +

+

+ Specifications +

+
    +
  • csda10f - Default
  • +
+

+ Joint limits and maximum joint velocities are based on the information + found in the online. + All urdfs are based on the default motion and joint velocity limits, + unless noted otherwise. +

+

+ Before using any of the configuration files and / or meshes included + in this package, be sure to check they are correct for the particular + robot model and configuration you intend to use them with. +

+
+ Amrith Ganesh + Amrith Ganesh + Amrith Ganesh + + BSD + + http://ros.org/wiki/motoman_sda10f_support + https://github.com/ros-industrial/motoman/issues + https://github.com/ros-industrial/motoman + + catkin + roslaunch + joint_state_publisher + motoman_driver + robot_state_publisher + rviz + xacro + + + + +
diff --git a/motoman_csda10f_support/urdf/arm_macro.xacro b/motoman_csda10f_support/urdf/arm_macro.xacro new file mode 100644 index 00000000..2af4f246 --- /dev/null +++ b/motoman_csda10f_support/urdf/arm_macro.xacro @@ -0,0 +1,176 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/motoman_csda10f_support/urdf/common_torso_macro.xacro b/motoman_csda10f_support/urdf/common_torso_macro.xacro new file mode 100644 index 00000000..62e5f9fa --- /dev/null +++ b/motoman_csda10f_support/urdf/common_torso_macro.xacro @@ -0,0 +1,77 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/motoman_csda10f_support/urdf/csda10f.xacro b/motoman_csda10f_support/urdf/csda10f.xacro new file mode 100644 index 00000000..f9b008ff --- /dev/null +++ b/motoman_csda10f_support/urdf/csda10f.xacro @@ -0,0 +1,7 @@ + + + + + + + diff --git a/motoman_csda10f_support/urdf/csda10f_macro.xacro b/motoman_csda10f_support/urdf/csda10f_macro.xacro new file mode 100644 index 00000000..b88dd722 --- /dev/null +++ b/motoman_csda10f_support/urdf/csda10f_macro.xacro @@ -0,0 +1,19 @@ + + + + + + + + + + + + + + + + + + +