From 3e4b9c9d0fa8af76b97cb1d758908be3f8cbae78 Mon Sep 17 00:00:00 2001 From: Johnkey00 <1176023870@qq.com> Date: Tue, 18 Jun 2024 16:28:23 +0800 Subject: [PATCH] add 280 m5 gazebo for melodic --- .../mycobot_280_gazebo_moveit/CMakeLists.txt | 10 + .../config/cartesian_limits.yaml | 5 + .../config/chomp_planning.yaml | 18 + .../config/fake_controllers.yaml | 13 + .../config/firefighter.srdf | 49 ++ .../config/joint_limits.yaml | 34 + .../config/kinematics.yaml | 4 + .../config/ompl_planning.yaml | 147 ++++ .../config/ros_controllers.yaml | 55 ++ .../config/sensors_3d.yaml | 23 + .../launch/chomp_planning_pipeline.launch.xml | 30 + .../launch/default_warehouse_db.launch | 15 + .../launch/demo.launch | 67 ++ .../launch/demo_gazebo.launch | 74 ++ .../fake_moveit_controller_manager.launch.xml | 12 + ...ghter_moveit_controller_manager.launch.xml | 7 + ...refighter_moveit_sensor_manager.launch.xml | 3 + .../launch/follower.launch | 38 + .../launch/gazebo.launch | 23 + .../launch/joystick_control.launch | 17 + .../launch/move_group.launch | 84 +++ .../launch/moveit.rviz | 689 ++++++++++++++++++ .../launch/moveit_rviz.launch | 15 + .../launch/ompl_planning_pipeline.launch.xml | 30 + ...otion_planner_planning_pipeline.launch.xml | 28 + .../launch/planning_context.launch | 26 + .../launch/planning_pipeline.launch.xml | 19 + .../launch/ros_controllers.launch | 14 + .../launch/run_benchmark_ompl.launch | 21 + .../launch/sensor_manager.launch.xml | 17 + .../launch/setup_assistant.launch | 15 + .../launch/trajectory_execution.launch.xml | 23 + .../launch/warehouse.launch | 15 + .../launch/warehouse_settings.launch.xml | 16 + .../mycobot_280_gazebo_moveit/package.xml | 37 + .../scripts/controller_interface.py | 98 +++ .../scripts/follow_display.py | 257 +++++++ .../scripts/slider_control.py | 56 ++ .../scripts/slider_control_gazebo.py | 66 ++ .../urdf/mycobot/mycobot_280_m5_gazebo.urdf | 323 ++++++++ 40 files changed, 2493 insertions(+) create mode 100644 mycobot_280/mycobot_280_gazebo_moveit/CMakeLists.txt create mode 100644 mycobot_280/mycobot_280_gazebo_moveit/config/cartesian_limits.yaml create mode 100644 mycobot_280/mycobot_280_gazebo_moveit/config/chomp_planning.yaml create mode 100644 mycobot_280/mycobot_280_gazebo_moveit/config/fake_controllers.yaml create mode 100644 mycobot_280/mycobot_280_gazebo_moveit/config/firefighter.srdf create mode 100644 mycobot_280/mycobot_280_gazebo_moveit/config/joint_limits.yaml create mode 100644 mycobot_280/mycobot_280_gazebo_moveit/config/kinematics.yaml create mode 100644 mycobot_280/mycobot_280_gazebo_moveit/config/ompl_planning.yaml create mode 100644 mycobot_280/mycobot_280_gazebo_moveit/config/ros_controllers.yaml create mode 100644 mycobot_280/mycobot_280_gazebo_moveit/config/sensors_3d.yaml create mode 100644 mycobot_280/mycobot_280_gazebo_moveit/launch/chomp_planning_pipeline.launch.xml create mode 100644 mycobot_280/mycobot_280_gazebo_moveit/launch/default_warehouse_db.launch create mode 100644 mycobot_280/mycobot_280_gazebo_moveit/launch/demo.launch create mode 100644 mycobot_280/mycobot_280_gazebo_moveit/launch/demo_gazebo.launch create mode 100644 mycobot_280/mycobot_280_gazebo_moveit/launch/fake_moveit_controller_manager.launch.xml create mode 100644 mycobot_280/mycobot_280_gazebo_moveit/launch/firefighter_moveit_controller_manager.launch.xml create mode 100644 mycobot_280/mycobot_280_gazebo_moveit/launch/firefighter_moveit_sensor_manager.launch.xml create mode 100644 mycobot_280/mycobot_280_gazebo_moveit/launch/follower.launch create mode 100644 mycobot_280/mycobot_280_gazebo_moveit/launch/gazebo.launch create mode 100644 mycobot_280/mycobot_280_gazebo_moveit/launch/joystick_control.launch create mode 100644 mycobot_280/mycobot_280_gazebo_moveit/launch/move_group.launch create mode 100644 mycobot_280/mycobot_280_gazebo_moveit/launch/moveit.rviz create mode 100644 mycobot_280/mycobot_280_gazebo_moveit/launch/moveit_rviz.launch create mode 100644 mycobot_280/mycobot_280_gazebo_moveit/launch/ompl_planning_pipeline.launch.xml create mode 100644 mycobot_280/mycobot_280_gazebo_moveit/launch/pilz_industrial_motion_planner_planning_pipeline.launch.xml create mode 100644 mycobot_280/mycobot_280_gazebo_moveit/launch/planning_context.launch create mode 100644 mycobot_280/mycobot_280_gazebo_moveit/launch/planning_pipeline.launch.xml create mode 100644 mycobot_280/mycobot_280_gazebo_moveit/launch/ros_controllers.launch create mode 100644 mycobot_280/mycobot_280_gazebo_moveit/launch/run_benchmark_ompl.launch create mode 100644 mycobot_280/mycobot_280_gazebo_moveit/launch/sensor_manager.launch.xml create mode 100644 mycobot_280/mycobot_280_gazebo_moveit/launch/setup_assistant.launch create mode 100644 mycobot_280/mycobot_280_gazebo_moveit/launch/trajectory_execution.launch.xml create mode 100644 mycobot_280/mycobot_280_gazebo_moveit/launch/warehouse.launch create mode 100644 mycobot_280/mycobot_280_gazebo_moveit/launch/warehouse_settings.launch.xml create mode 100644 mycobot_280/mycobot_280_gazebo_moveit/package.xml create mode 100644 mycobot_280/mycobot_280_gazebo_moveit/scripts/controller_interface.py create mode 100755 mycobot_280/mycobot_280_gazebo_moveit/scripts/follow_display.py create mode 100755 mycobot_280/mycobot_280_gazebo_moveit/scripts/slider_control.py create mode 100755 mycobot_280/mycobot_280_gazebo_moveit/scripts/slider_control_gazebo.py create mode 100644 mycobot_description/urdf/mycobot/mycobot_280_m5_gazebo.urdf diff --git a/mycobot_280/mycobot_280_gazebo_moveit/CMakeLists.txt b/mycobot_280/mycobot_280_gazebo_moveit/CMakeLists.txt new file mode 100644 index 00000000..f2ab477d --- /dev/null +++ b/mycobot_280/mycobot_280_gazebo_moveit/CMakeLists.txt @@ -0,0 +1,10 @@ +cmake_minimum_required(VERSION 3.1.3) +project(mycobot_280_gazebo_moveit) + +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/mycobot_280/mycobot_280_gazebo_moveit/config/cartesian_limits.yaml b/mycobot_280/mycobot_280_gazebo_moveit/config/cartesian_limits.yaml new file mode 100644 index 00000000..7df72f69 --- /dev/null +++ b/mycobot_280/mycobot_280_gazebo_moveit/config/cartesian_limits.yaml @@ -0,0 +1,5 @@ +cartesian_limits: + max_trans_vel: 1 + max_trans_acc: 2.25 + max_trans_dec: -5 + max_rot_vel: 1.57 diff --git a/mycobot_280/mycobot_280_gazebo_moveit/config/chomp_planning.yaml b/mycobot_280/mycobot_280_gazebo_moveit/config/chomp_planning.yaml new file mode 100644 index 00000000..75258e53 --- /dev/null +++ b/mycobot_280/mycobot_280_gazebo_moveit/config/chomp_planning.yaml @@ -0,0 +1,18 @@ +planning_time_limit: 10.0 +max_iterations: 200 +max_iterations_after_collision_free: 5 +smoothness_cost_weight: 0.1 +obstacle_cost_weight: 1.0 +learning_rate: 0.01 +smoothness_cost_velocity: 0.0 +smoothness_cost_acceleration: 1.0 +smoothness_cost_jerk: 0.0 +ridge_factor: 0.01 +use_pseudo_inverse: false +pseudo_inverse_ridge_factor: 1e-4 +joint_update_limit: 0.1 +collision_clearence: 0.2 +collision_threshold: 0.07 +use_stochastic_descent: true +enable_failure_recovery: true +max_recovery_attempts: 5 \ No newline at end of file diff --git a/mycobot_280/mycobot_280_gazebo_moveit/config/fake_controllers.yaml b/mycobot_280/mycobot_280_gazebo_moveit/config/fake_controllers.yaml new file mode 100644 index 00000000..b76be65e --- /dev/null +++ b/mycobot_280/mycobot_280_gazebo_moveit/config/fake_controllers.yaml @@ -0,0 +1,13 @@ +controller_list: + - name: fake_mycobot_280_gazebo_controller + type: $(arg fake_execution_type) + joints: + - joint2_to_joint1 + - joint3_to_joint2 + - joint4_to_joint3 + - joint5_to_joint4 + - joint6_to_joint5 + - joint6output_to_joint6 +initial: # Define initial robot poses. + - group: mycobot_280_gazebo + pose: HOME \ No newline at end of file diff --git a/mycobot_280/mycobot_280_gazebo_moveit/config/firefighter.srdf b/mycobot_280/mycobot_280_gazebo_moveit/config/firefighter.srdf new file mode 100644 index 00000000..52969a8a --- /dev/null +++ b/mycobot_280/mycobot_280_gazebo_moveit/config/firefighter.srdf @@ -0,0 +1,49 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/mycobot_280/mycobot_280_gazebo_moveit/config/joint_limits.yaml b/mycobot_280/mycobot_280_gazebo_moveit/config/joint_limits.yaml new file mode 100644 index 00000000..6e9612a5 --- /dev/null +++ b/mycobot_280/mycobot_280_gazebo_moveit/config/joint_limits.yaml @@ -0,0 +1,34 @@ +# 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: + joint2_to_joint1: + has_velocity_limits: false + max_velocity: 0 + has_acceleration_limits: false + max_acceleration: 0 + joint3_to_joint2: + has_velocity_limits: false + max_velocity: 0 + has_acceleration_limits: false + max_acceleration: 0 + joint4_to_joint3: + has_velocity_limits: false + max_velocity: 0 + has_acceleration_limits: false + max_acceleration: 0 + joint5_to_joint4: + has_velocity_limits: false + max_velocity: 0 + has_acceleration_limits: false + max_acceleration: 0 + joint6_to_joint5: + has_velocity_limits: false + max_velocity: 0 + has_acceleration_limits: false + max_acceleration: 0 + joint6output_to_joint6: + has_velocity_limits: false + max_velocity: 0 + has_acceleration_limits: false + max_acceleration: 0 \ No newline at end of file diff --git a/mycobot_280/mycobot_280_gazebo_moveit/config/kinematics.yaml b/mycobot_280/mycobot_280_gazebo_moveit/config/kinematics.yaml new file mode 100644 index 00000000..2bd31f50 --- /dev/null +++ b/mycobot_280/mycobot_280_gazebo_moveit/config/kinematics.yaml @@ -0,0 +1,4 @@ +mycobot_280_gazebo: + kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin + kinematics_solver_search_resolution: 0.005 + kinematics_solver_timeout: 0.005 \ No newline at end of file diff --git a/mycobot_280/mycobot_280_gazebo_moveit/config/ompl_planning.yaml b/mycobot_280/mycobot_280_gazebo_moveit/config/ompl_planning.yaml new file mode 100644 index 00000000..8e9a25ce --- /dev/null +++ b/mycobot_280/mycobot_280_gazebo_moveit/config/ompl_planning.yaml @@ -0,0 +1,147 @@ +planner_configs: + SBL: + type: geometric::SBL + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + EST: + type: geometric::EST + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0 setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + LBKPIECE: + type: geometric::LBKPIECE + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 + min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 + BKPIECE: + type: geometric::BKPIECE + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 + failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5 + min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 + KPIECE: + type: geometric::KPIECE + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + border_fraction: 0.9 # Fraction of time focused on boarder default: 0.9 (0.0,1.] + failed_expansion_score_factor: 0.5 # When extending motion fails, scale score by factor. default: 0.5 + min_valid_path_fraction: 0.5 # Accept partially valid moves above fraction. default: 0.5 + RRT: + type: geometric::RRT + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 + RRTConnect: + type: geometric::RRTConnect + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + RRTstar: + type: geometric::RRTstar + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 + delay_collision_checking: 1 # Stop collision checking as soon as C-free parent found. default 1 + TRRT: + type: geometric::TRRT + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability? default: 0.05 + max_states_failed: 10 # when to start increasing temp. default: 10 + temp_change_factor: 2.0 # how much to increase or decrease temp. default: 2.0 + min_temperature: 10e-10 # lower limit of temp change. default: 10e-10 + init_temperature: 10e-6 # initial temperature. default: 10e-6 + 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: + type: geometric::PRM + max_nearest_neighbors: 10 # use k nearest neighbors. default: 10 + PRMstar: + type: geometric::PRMstar + FMT: + type: geometric::FMT + num_samples: 1000 # number of states that the planner should sample. default: 1000 + radius_multiplier: 1.1 # multiplier used for the nearest neighbors search radius. default: 1.1 + nearest_k: 1 # use Knearest strategy. default: 1 + cache_cc: 1 # use collision checking cache. default: 1 + heuristics: 0 # activate cost to go heuristics. default: 0 + extended_fmt: 1 # activate the extended FMT*: adding new samples if planner does not finish successfully. default: 1 + BFMT: + type: geometric::BFMT + num_samples: 1000 # number of states that the planner should sample. default: 1000 + radius_multiplier: 1.0 # multiplier used for the nearest neighbors search radius. default: 1.0 + nearest_k: 1 # use the Knearest strategy. default: 1 + balanced: 0 # exploration strategy: balanced true expands one tree every iteration. False will select the tree with lowest maximum cost to go. default: 1 + optimality: 1 # termination strategy: optimality true finishes when the best possible path is found. Otherwise, the algorithm will finish when the first feasible path is found. default: 1 + heuristics: 1 # activates cost to go heuristics. default: 1 + cache_cc: 1 # use the collision checking cache. default: 1 + extended_fmt: 1 # Activates the extended FMT*: adding new samples if planner does not finish successfully. default: 1 + PDST: + type: geometric::PDST + STRIDE: + type: geometric::STRIDE + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + use_projected_distance: 0 # whether nearest neighbors are computed based on distances in a projection of the state rather distances in the state space itself. default: 0 + degree: 16 # desired degree of a node in the Geometric Near-neightbor Access Tree (GNAT). default: 16 + max_degree: 18 # max degree of a node in the GNAT. default: 12 + min_degree: 12 # min degree of a node in the GNAT. default: 12 + max_pts_per_leaf: 6 # max points per leaf in the GNAT. default: 6 + estimated_dimension: 0.0 # estimated dimension of the free space. default: 0.0 + min_valid_path_fraction: 0.2 # Accept partially valid moves above fraction. default: 0.2 + BiTRRT: + type: geometric::BiTRRT + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + temp_change_factor: 0.1 # how much to increase or decrease temp. default: 0.1 + init_temperature: 100 # initial temperature. default: 100 + 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: + type: geometric::LBTRRT + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + epsilon: 0.4 # optimality approximation factor. default: 0.4 + BiEST: + type: geometric::BiEST + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + ProjEST: + type: geometric::ProjEST + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + goal_bias: 0.05 # When close to goal select goal, with this probability. default: 0.05 + LazyPRM: + type: geometric::LazyPRM + range: 0.0 # Max motion added to tree. ==> maxDistance_ default: 0.0, if 0.0, set on setup() + LazyPRMstar: + type: geometric::LazyPRMstar + SPARS: + type: geometric::SPARS + stretch_factor: 3.0 # roadmap spanner stretch factor. multiplicative upper bound on path quality. It does not make sense to make this parameter more than 3. default: 3.0 + sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25 + dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001 + max_failures: 1000 # maximum consecutive failure limit. default: 1000 + SPARStwo: + type: geometric::SPARStwo + stretch_factor: 3.0 # roadmap spanner stretch factor. multiplicative upper bound on path quality. It does not make sense to make this parameter more than 3. default: 3.0 + sparse_delta_fraction: 0.25 # delta fraction for connection distance. This value represents the visibility range of sparse samples. default: 0.25 + dense_delta_fraction: 0.001 # delta fraction for interface detection. default: 0.001 + max_failures: 5000 # maximum consecutive failure limit. default: 5000 +mycobot_280_gazebo: + planner_configs: + - SBL + - EST + - LBKPIECE + - BKPIECE + - KPIECE + - RRT + - RRTConnect + - RRTstar + - TRRT + - PRM + - PRMstar + - FMT + - BFMT + - PDST + - STRIDE + - BiTRRT + - LBTRRT + - BiEST + - ProjEST + - LazyPRM + - LazyPRMstar + - SPARS + - SPARStwo diff --git a/mycobot_280/mycobot_280_gazebo_moveit/config/ros_controllers.yaml b/mycobot_280/mycobot_280_gazebo_moveit/config/ros_controllers.yaml new file mode 100644 index 00000000..c313d92a --- /dev/null +++ b/mycobot_280/mycobot_280_gazebo_moveit/config/ros_controllers.yaml @@ -0,0 +1,55 @@ +# Simulation settings for using moveit_sim_controllers +moveit_sim_hw_interface: + joint_model_group: mycobot_280_gazebo + joint_model_group_pose: HOME + +generic_hw_control_loop: + loop_hz: 300 + cycle_time_error_threshold: 0.01 +# Settings for ros_control hardware interface +hardware_interface: + joints: + - joint2_to_joint1 + - joint3_to_joint2 + - joint4_to_joint3 + - joint5_to_joint4 + - joint6_to_joint5 + - joint6output_to_joint6 + sim_control_mode: 0 # 0: position, 1: velocity +# Publish all joint states +# Creates the /joint_states topic necessary in ROS +joint_state_controller: + type: joint_state_controller/JointStateController + publish_rate: 50 + +# PID controller settings for each joint +gazebo_ros_control/pid_gains: + joint2_to_joint1: {p: 100.0, i: 0.01, d: 10.0} + joint3_to_joint2: {p: 100.0, i: 0.01, d: 10.0} + joint4_to_joint3: {p: 100.0, i: 0.01, d: 10.0} + joint5_to_joint4: {p: 100.0, i: 0.01, d: 10.0} + joint6_to_joint5: {p: 100.0, i: 0.01, d: 10.0} + joint6output_to_joint6: {p: 100.0, i: 0.01, d: 10.0} + +mycobot_position_controller: + type: position_controllers/JointTrajectoryController + joints: + - joint2_to_joint1 + - joint3_to_joint2 + - joint4_to_joint3 + - joint5_to_joint4 + - joint6_to_joint5 + - joint6output_to_joint6 + +controller_list: + - name: mycobot_position_controller + action_ns: follow_joint_trajectory + type: FollowJointTrajectory + default: true + joints: + - joint2_to_joint1 + - joint3_to_joint2 + - joint4_to_joint3 + - joint5_to_joint4 + - joint6_to_joint5 + - joint6output_to_joint6 diff --git a/mycobot_280/mycobot_280_gazebo_moveit/config/sensors_3d.yaml b/mycobot_280/mycobot_280_gazebo_moveit/config/sensors_3d.yaml new file mode 100644 index 00000000..0713b613 --- /dev/null +++ b/mycobot_280/mycobot_280_gazebo_moveit/config/sensors_3d.yaml @@ -0,0 +1,23 @@ +# The name of this file shouldn't be changed, or else the Setup Assistant won't detect it +sensors: + - filtered_cloud_topic: filtered_cloud + max_range: 5.0 + max_update_rate: 1.0 + padding_offset: 0.1 + padding_scale: 1.0 + point_cloud_topic: /head_mount_kinect/depth_registered/points + point_subsample: 1 + sensor_plugin: occupancy_map_monitor/PointCloudOctomapUpdater + - far_clipping_plane_distance: 5.0 + filtered_cloud_topic: filtered_cloud + image_topic: /head_mount_kinect/depth_registered/image_raw + max_range: 5.0 + max_update_rate: 1.0 + near_clipping_plane_distance: 0.3 + padding_offset: 0.03 + padding_scale: 4.0 + point_cloud_topic: /head_mount_kinect/depth_registered/points + point_subsample: 1 + queue_size: 5 + sensor_plugin: occupancy_map_monitor/DepthImageOctomapUpdater + shadow_threshold: 0.2 \ No newline at end of file diff --git a/mycobot_280/mycobot_280_gazebo_moveit/launch/chomp_planning_pipeline.launch.xml b/mycobot_280/mycobot_280_gazebo_moveit/launch/chomp_planning_pipeline.launch.xml new file mode 100644 index 00000000..688392db --- /dev/null +++ b/mycobot_280/mycobot_280_gazebo_moveit/launch/chomp_planning_pipeline.launch.xml @@ -0,0 +1,30 @@ + + + + + + + + + + + + + + + + + + + + + + diff --git a/mycobot_280/mycobot_280_gazebo_moveit/launch/default_warehouse_db.launch b/mycobot_280/mycobot_280_gazebo_moveit/launch/default_warehouse_db.launch new file mode 100644 index 00000000..c0e8b1f6 --- /dev/null +++ b/mycobot_280/mycobot_280_gazebo_moveit/launch/default_warehouse_db.launch @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + + diff --git a/mycobot_280/mycobot_280_gazebo_moveit/launch/demo.launch b/mycobot_280/mycobot_280_gazebo_moveit/launch/demo.launch new file mode 100644 index 00000000..b79be6fd --- /dev/null +++ b/mycobot_280/mycobot_280_gazebo_moveit/launch/demo.launch @@ -0,0 +1,67 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [move_group/fake_controller_joint_states] + + + [move_group/fake_controller_joint_states] + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/mycobot_280/mycobot_280_gazebo_moveit/launch/demo_gazebo.launch b/mycobot_280/mycobot_280_gazebo_moveit/launch/demo_gazebo.launch new file mode 100644 index 00000000..e727e7d1 --- /dev/null +++ b/mycobot_280/mycobot_280_gazebo_moveit/launch/demo_gazebo.launch @@ -0,0 +1,74 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + [move_group/fake_controller_joint_states] + [/joint_states] + + + [move_group/fake_controller_joint_states] + [/joint_states] + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/mycobot_280/mycobot_280_gazebo_moveit/launch/fake_moveit_controller_manager.launch.xml b/mycobot_280/mycobot_280_gazebo_moveit/launch/fake_moveit_controller_manager.launch.xml new file mode 100644 index 00000000..c6827f8d --- /dev/null +++ b/mycobot_280/mycobot_280_gazebo_moveit/launch/fake_moveit_controller_manager.launch.xml @@ -0,0 +1,12 @@ + + + + + + + + + + + + diff --git a/mycobot_280/mycobot_280_gazebo_moveit/launch/firefighter_moveit_controller_manager.launch.xml b/mycobot_280/mycobot_280_gazebo_moveit/launch/firefighter_moveit_controller_manager.launch.xml new file mode 100644 index 00000000..5cf71929 --- /dev/null +++ b/mycobot_280/mycobot_280_gazebo_moveit/launch/firefighter_moveit_controller_manager.launch.xml @@ -0,0 +1,7 @@ + + + + + + + diff --git a/mycobot_280/mycobot_280_gazebo_moveit/launch/firefighter_moveit_sensor_manager.launch.xml b/mycobot_280/mycobot_280_gazebo_moveit/launch/firefighter_moveit_sensor_manager.launch.xml new file mode 100644 index 00000000..5d02698d --- /dev/null +++ b/mycobot_280/mycobot_280_gazebo_moveit/launch/firefighter_moveit_sensor_manager.launch.xml @@ -0,0 +1,3 @@ + + + diff --git a/mycobot_280/mycobot_280_gazebo_moveit/launch/follower.launch b/mycobot_280/mycobot_280_gazebo_moveit/launch/follower.launch new file mode 100644 index 00000000..95437a9d --- /dev/null +++ b/mycobot_280/mycobot_280_gazebo_moveit/launch/follower.launch @@ -0,0 +1,38 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/mycobot_280/mycobot_280_gazebo_moveit/launch/gazebo.launch b/mycobot_280/mycobot_280_gazebo_moveit/launch/gazebo.launch new file mode 100644 index 00000000..6fcf9e81 --- /dev/null +++ b/mycobot_280/mycobot_280_gazebo_moveit/launch/gazebo.launch @@ -0,0 +1,23 @@ + + + + + + + + + + + + + + + + + + + + + + diff --git a/mycobot_280/mycobot_280_gazebo_moveit/launch/joystick_control.launch b/mycobot_280/mycobot_280_gazebo_moveit/launch/joystick_control.launch new file mode 100644 index 00000000..9411f6e6 --- /dev/null +++ b/mycobot_280/mycobot_280_gazebo_moveit/launch/joystick_control.launch @@ -0,0 +1,17 @@ + + + + + + + + + + + + + + + + + diff --git a/mycobot_280/mycobot_280_gazebo_moveit/launch/move_group.launch b/mycobot_280/mycobot_280_gazebo_moveit/launch/move_group.launch new file mode 100644 index 00000000..7195966e --- /dev/null +++ b/mycobot_280/mycobot_280_gazebo_moveit/launch/move_group.launch @@ -0,0 +1,84 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/mycobot_280/mycobot_280_gazebo_moveit/launch/moveit.rviz b/mycobot_280/mycobot_280_gazebo_moveit/launch/moveit.rviz new file mode 100644 index 00000000..7070bbab --- /dev/null +++ b/mycobot_280/mycobot_280_gazebo_moveit/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: g_base + 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: /g_base + 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/mycobot_280/mycobot_280_gazebo_moveit/launch/moveit_rviz.launch b/mycobot_280/mycobot_280_gazebo_moveit/launch/moveit_rviz.launch new file mode 100644 index 00000000..a4605c03 --- /dev/null +++ b/mycobot_280/mycobot_280_gazebo_moveit/launch/moveit_rviz.launch @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + diff --git a/mycobot_280/mycobot_280_gazebo_moveit/launch/ompl_planning_pipeline.launch.xml b/mycobot_280/mycobot_280_gazebo_moveit/launch/ompl_planning_pipeline.launch.xml new file mode 100644 index 00000000..5c01afcf --- /dev/null +++ b/mycobot_280/mycobot_280_gazebo_moveit/launch/ompl_planning_pipeline.launch.xml @@ -0,0 +1,30 @@ + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/mycobot_280/mycobot_280_gazebo_moveit/launch/pilz_industrial_motion_planner_planning_pipeline.launch.xml b/mycobot_280/mycobot_280_gazebo_moveit/launch/pilz_industrial_motion_planner_planning_pipeline.launch.xml new file mode 100644 index 00000000..ac6272e2 --- /dev/null +++ b/mycobot_280/mycobot_280_gazebo_moveit/launch/pilz_industrial_motion_planner_planning_pipeline.launch.xml @@ -0,0 +1,28 @@ + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/mycobot_280/mycobot_280_gazebo_moveit/launch/planning_context.launch b/mycobot_280/mycobot_280_gazebo_moveit/launch/planning_context.launch new file mode 100644 index 00000000..d4239cb9 --- /dev/null +++ b/mycobot_280/mycobot_280_gazebo_moveit/launch/planning_context.launch @@ -0,0 +1,26 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/mycobot_280/mycobot_280_gazebo_moveit/launch/planning_pipeline.launch.xml b/mycobot_280/mycobot_280_gazebo_moveit/launch/planning_pipeline.launch.xml new file mode 100644 index 00000000..a97b5ae8 --- /dev/null +++ b/mycobot_280/mycobot_280_gazebo_moveit/launch/planning_pipeline.launch.xml @@ -0,0 +1,19 @@ + + + + + + + + + + + + + + + + + + diff --git a/mycobot_280/mycobot_280_gazebo_moveit/launch/ros_controllers.launch b/mycobot_280/mycobot_280_gazebo_moveit/launch/ros_controllers.launch new file mode 100644 index 00000000..b772f9be --- /dev/null +++ b/mycobot_280/mycobot_280_gazebo_moveit/launch/ros_controllers.launch @@ -0,0 +1,14 @@ + + + + + + + + + + + + \ No newline at end of file diff --git a/mycobot_280/mycobot_280_gazebo_moveit/launch/run_benchmark_ompl.launch b/mycobot_280/mycobot_280_gazebo_moveit/launch/run_benchmark_ompl.launch new file mode 100644 index 00000000..eb8d7227 --- /dev/null +++ b/mycobot_280/mycobot_280_gazebo_moveit/launch/run_benchmark_ompl.launch @@ -0,0 +1,21 @@ + + + + + + + + + + + + + + + + + + + + + diff --git a/mycobot_280/mycobot_280_gazebo_moveit/launch/sensor_manager.launch.xml b/mycobot_280/mycobot_280_gazebo_moveit/launch/sensor_manager.launch.xml new file mode 100644 index 00000000..fca6bd1d --- /dev/null +++ b/mycobot_280/mycobot_280_gazebo_moveit/launch/sensor_manager.launch.xml @@ -0,0 +1,17 @@ + + + + + + + + + + + + + + + + + diff --git a/mycobot_280/mycobot_280_gazebo_moveit/launch/setup_assistant.launch b/mycobot_280/mycobot_280_gazebo_moveit/launch/setup_assistant.launch new file mode 100644 index 00000000..7a1128f0 --- /dev/null +++ b/mycobot_280/mycobot_280_gazebo_moveit/launch/setup_assistant.launch @@ -0,0 +1,15 @@ + + + + + + + + + + + + diff --git a/mycobot_280/mycobot_280_gazebo_moveit/launch/trajectory_execution.launch.xml b/mycobot_280/mycobot_280_gazebo_moveit/launch/trajectory_execution.launch.xml new file mode 100644 index 00000000..ce29ebc3 --- /dev/null +++ b/mycobot_280/mycobot_280_gazebo_moveit/launch/trajectory_execution.launch.xml @@ -0,0 +1,23 @@ + + + + + + + + + + + + + + + + + + + + + + diff --git a/mycobot_280/mycobot_280_gazebo_moveit/launch/warehouse.launch b/mycobot_280/mycobot_280_gazebo_moveit/launch/warehouse.launch new file mode 100644 index 00000000..434ee75f --- /dev/null +++ b/mycobot_280/mycobot_280_gazebo_moveit/launch/warehouse.launch @@ -0,0 +1,15 @@ + + + + + + + + + + + + + + + diff --git a/mycobot_280/mycobot_280_gazebo_moveit/launch/warehouse_settings.launch.xml b/mycobot_280/mycobot_280_gazebo_moveit/launch/warehouse_settings.launch.xml new file mode 100644 index 00000000..e473b083 --- /dev/null +++ b/mycobot_280/mycobot_280_gazebo_moveit/launch/warehouse_settings.launch.xml @@ -0,0 +1,16 @@ + + + + + + + + + + + + + + + + diff --git a/mycobot_280/mycobot_280_gazebo_moveit/package.xml b/mycobot_280/mycobot_280_gazebo_moveit/package.xml new file mode 100644 index 00000000..bc03b789 --- /dev/null +++ b/mycobot_280/mycobot_280_gazebo_moveit/package.xml @@ -0,0 +1,37 @@ + + + mycobot_280_gazebo_moveit + 0.3.0 + + An automatically generated package with all the configuration and launch files for using the firefighter with the MoveIt! Motion Planning Framework + + Junjie + Junjie + + 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_ompl + moveit_ros_visualization + moveit_setup_assistant + moveit_simple_controller_manager + joint_state_publisher + joint_state_publisher_gui + robot_state_publisher + rviz + tf2_ros + xacro + + + mycobot_description + + + diff --git a/mycobot_280/mycobot_280_gazebo_moveit/scripts/controller_interface.py b/mycobot_280/mycobot_280_gazebo_moveit/scripts/controller_interface.py new file mode 100644 index 00000000..631dc1e2 --- /dev/null +++ b/mycobot_280/mycobot_280_gazebo_moveit/scripts/controller_interface.py @@ -0,0 +1,98 @@ +#!/usr/bin/env python2 +# -*- coding: UTF-8 -*- + +import Tkinter +import rospy +from Tkinter import * +from std_msgs.msg import Header +from sensor_msgs.msg import JointState +from pymycobot.mycobot import MyCobot + +def talker(): + rospy.init_node("display", anonymous=True) + + print("Try connect real mycobot...") + port = rospy.get_param("~port", "/dev/ttyUSB0") + baud = rospy.get_param("~baud", 115200) + print("port: {}, baud: {}\n".format(port, baud)) + try: + mycobot = MyCobot(port, baud) + except Exception as e: + print(e) + print( + """\ + \rTry connect mycobot failed! + \rPlease check wether connected with mycobot. + \rPlease chckt wether the port or baud is right. + """ + ) + exit(1) + mycobot.release_all_servos() + time.sleep(0.1) + print("Rlease all servos over.\n") + + pub = rospy.Publisher("joint_states", JointState, queue_size = 10) + rate = rospy.Rate(30) + + joint_state_send = JointState() + joint_state_send.header = Header() + + joint_state_send.name = [ + "joint2_to_joint1", + "joint3_to_joint2", + "joint4_to_joint3", + "joint5_to_joint4", + "joint6_to_joint5", + "joint6output_to_joint6", + ] + joint_state_send.velocity = [0] * len(joint_state_send.name) + joint_state_send.effort = [] + + print("publishing ...") + while not rospy.is_shutdown(): + joint_state_send.header.stamp = rospy.Time.now() + + angles = mycobot.get_radians() + if angles: + data_list = [value for value in angles] + print(data_list) + joint_state_send.position = data_list + pub.publish(joint_state_send) + rate.sleep() + + +if __name__ == "__main__": + talker() + window = Tkinter.Tk() + window.title("Controller GUI") + window.geometry("230x330") + window.resizable(False, False) + + # Label Components + coord_label1 = Label(window, text = "joint2_to_joint1") + coord_label1.place(x = 20, y = 20, width = 100, height = 30) + coord_label2 = Label(window, text = "joint3_to_joint2") + coord_label2.place(x = 20, y = 70, width = 100, height = 30) + coord_label3 = Label(window, text = "joint4_to_joint3") + coord_label3.place(x = 20, y = 120, width = 100, height = 30) + coord_label4 = Label(window, text = "joint5_to_joint4") + coord_label4.place(x = 20, y = 170, width = 100, height = 30) + coord_label5 = Label(window, text = "joint6_to_joint5") + coord_label5.place(x = 20, y = 220, width = 100, height = 30) + coord_label6 = Label(window, text = "joint6output_to_joint6") + coord_label6.place(x = 20, y = 280, width = 100, height = 30) + # Entry Components + coord_entry1 = Entry(window, textvariable = 0.00) + coord_entry1.place(x = 130, y = 20, width = 80, height = 30) + coord_entry2 = Entry(window, textvariable = 0.00) + coord_entry2.place(x = 130, y = 70, width = 80, height = 30) + coord_entry3 = Entry(window, textvariable = 0.00) + coord_entry3.place(x = 130, y = 120, width = 80, height = 30) + coord_entry4 = Entry(window, textvariable = 0.00) + coord_entry4.place(x = 130, y = 170, width = 80, height = 30) + coord_entry5 = Entry(window, textvariable = 0.00) + coord_entry5.place(x = 130, y = 220, width = 80, height = 30) + coord_entry6 = Entry(window, textvariable = 0.00) + coord_entry6.place(x = 130, y = 270, width = 80, height = 30) + + window.mainloop() \ No newline at end of file diff --git a/mycobot_280/mycobot_280_gazebo_moveit/scripts/follow_display.py b/mycobot_280/mycobot_280_gazebo_moveit/scripts/follow_display.py new file mode 100755 index 00000000..1ee3a3d5 --- /dev/null +++ b/mycobot_280/mycobot_280_gazebo_moveit/scripts/follow_display.py @@ -0,0 +1,257 @@ +#!/usr/bin/env python2 +# -*- coding: utf-8 -*- + +import time +import rospy +from sensor_msgs.msg import JointState +from std_msgs.msg import Header +from visualization_msgs.msg import Marker +from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint +from pymycobot.mycobot import MyCobot +import threading +import Tkinter +from Tkinter import * +from pymycobot.common import ProtocolCode +import math + +joint_names = [ + "joint2_to_joint1", + "joint3_to_joint2", + "joint4_to_joint3", + "joint5_to_joint4", + "joint6_to_joint5", + "joint6output_to_joint6", +] + +change_list = [] + +def talker(): + rospy.init_node("display", anonymous=True) + + global mycobot + + print("Try connect real mycobot...") + port = rospy.get_param("~port", "/dev/ttyUSB0") + baud = rospy.get_param("~baud", 115200) + print("port: {}, baud: {}\n".format(port, baud)) + try: + mycobot = MyCobot(port, baud) + except Exception as e: + print(e) + print( + """\ + \rTry connect mycobot failed! + \rPlease check wether connected with mycobot. + \rPlease chckt wether the port or baud is right. + """ + ) + exit(1) + mycobot.release_all_servos() + time.sleep(0.1) + print("Rlease all servos over.\n") + + pub = rospy.Publisher("joint_states", JointState, queue_size=10) + # pub_marker = rospy.Publisher("visualization_marker", Marker, queue_size=10) + pub_command = rospy.Publisher("/mycobot_position_controller/command", JointTrajectory, queue_size=10) + rate = rospy.Rate(30) # 30hz + + # pub joint state + joint_state_send = JointState() + joint_state_send.header = Header() + joint_state_send.name = joint_names + joint_state_send.velocity = [0] * len(joint_state_send.name) + joint_state_send.effort = [] + + # marker_ = Marker() + # marker_.header.frame_id = "/joint1" + # marker_.ns = "my_namespace" + + print("publishing ...") + + global coord_entry1, coord_entry2, coord_entry3, coord_entry4, coord_entry5, coord_entry6, prev_angles + global coord_scale1, coord_scale2, coord_scale3, coord_scale4, coord_scale5, coord_scale6 + prev_angles = [] + while not rospy.is_shutdown(): + joint_state_send.header.stamp = rospy.Time.now() + + # angles = mycobot.get_radians() + get_angles = mycobot._mesg(ProtocolCode.GET_ANGLES, has_reply=True) + if get_angles is None: continue + angles = [round(angle * (math.pi / 180), 3) for angle in get_angles] + if angles: + data_list = [value for value in angles] + + joint_state_send.position = data_list + pub.publish(joint_state_send) + + # print(data_list[0]) + # print(data_list[1]) + if len(prev_angles) == 0: + prev_angles = data_list + coord_entry1.insert(Tkinter.END, round(data_list[0] * 180 / math.pi, 2)) + coord_entry2.insert(Tkinter.END, round(data_list[1] * 180 / math.pi, 2)) + coord_entry3.insert(Tkinter.END, round(data_list[2] * 180 / math.pi, 2)) + coord_entry4.insert(Tkinter.END, round(data_list[3] * 180 / math.pi, 2)) + coord_entry5.insert(Tkinter.END, round(data_list[4] * 180 / math.pi, 2)) + coord_entry6.insert(Tkinter.END, round(data_list[5] * 180 / math.pi, 2)) + coord_scale1.set(int(data_list[0] * 180 / math.pi)) + coord_scale2.set(int(data_list[1] * 180 / math.pi)) + coord_scale3.set(int(data_list[2] * 180 / math.pi)) + coord_scale4.set(int(data_list[3] * 180 / math.pi)) + coord_scale5.set(int(data_list[4] * 180 / math.pi)) + coord_scale6.set(int(data_list[5] * 180 / math.pi)) + continue + if not prev_angles[0] == data_list[0]: + coord_entry1.delete(0, Tkinter.END) + coord_entry1.insert(Tkinter.END, round(data_list[0] * 180 / math.pi, 2)) + # coord_scale1.set(int(data_list[0] * 180 / math.pi)) + if not prev_angles[1] == data_list[1]: + coord_entry2.delete(0, Tkinter.END) + coord_entry2.insert(Tkinter.END, round(data_list[1] * 180 / math.pi, 2)) + # coord_scale2.set(int(data_list[1] * 180 / math.pi)) + if not prev_angles[2] == data_list[2]: + coord_entry3.delete(0, Tkinter.END) + coord_entry3.insert(Tkinter.END, round(data_list[2] * 180 / math.pi, 2)) + # coord_scale3.set(int(data_list[2] * 180 / math.pi)) + if not prev_angles[3] == data_list[3]: + coord_entry4.delete(0, Tkinter.END) + coord_entry4.insert(Tkinter.END, round(data_list[3] * 180 / math.pi, 2)) + # coord_scale4.set(int(data_list[3] * 180 / math.pi)) + if not prev_angles[4] == data_list[4]: + coord_entry5.delete(0, Tkinter.END) + coord_entry5.insert(Tkinter.END, round(data_list[4] * 180 / math.pi, 2)) + # coord_scale5.set(int(data_list[4] * 180 / math.pi)) + if not prev_angles[5] == data_list[5]: + coord_entry6.delete(0, Tkinter.END) + coord_entry6.insert(Tkinter.END, round(data_list[5] * 180 / math.pi, 2)) + # coord_scale6.set(int(data_list[5] * 180 / math.pi)) + prev_angles = data_list + + global change_list + if len(change_list) != 0: + # print(change_list) + mycobot.send_angles(change_list, 25) + change_list = [] + + # Create JointTrajectory message + traj_msg = JointTrajectory() + traj_msg.header.stamp = rospy.Time.now() + traj_msg.joint_names = joint_names + + point = JointTrajectoryPoint() + point.positions = data_list + point.velocities = [0.0] * len(joint_names) + point.time_from_start = rospy.Duration(0.1) # Set a small duration to continuously update + + traj_msg.points.append(point) + pub_command.publish(traj_msg) + + # coords = mycobot.get_coords() + + # # Marker + # marker_.header.stamp = rospy.Time.now() + # marker_.type = marker_.SPHERE + # marker_.action = marker_.ADD + # marker_.scale.x = 0.04 + # marker_.scale.y = 0.04 + # marker_.scale.z = 0.04 + + # if not coords: + # coords = [0, 0, 0, 0, 0, 0] + # rospy.loginfo("error [101]: cannot get coord values") + + # marker_.pose.position.x = coords[1] / 1000 * -1 + # marker_.pose.position.y = coords[0] / 1000 + # marker_.pose.position.z = coords[2] / 1000 + + # marker_.color.a = 1.0 + # marker_.color.g = 1.0 + # pub_marker.publish(marker_) + + rate.sleep() + +def move_arm(): + global prev_angles, change_list + global coord_scale1, coord_scale2, coord_scale3, coord_scale4, coord_scale5, coord_scale6 + new_data_list = [float(coord_entry1.get()),float(coord_entry2.get()),float(coord_entry3.get()),float(coord_entry4.get()),float(coord_entry5.get()),float(coord_entry6.get())] + new_data_list = [round(num, 2) for num in new_data_list] + # print("new_data_list %s" % new_data_list) + prev_angles = new_data_list + change_list = new_data_list + coord_scale1.set(int(new_data_list[0])) + coord_scale2.set(int(new_data_list[1])) + coord_scale3.set(int(new_data_list[2])) + coord_scale4.set(int(new_data_list[3])) + coord_scale5.set(int(new_data_list[4])) + coord_scale6.set(int(new_data_list[5])) + # print("mycobot_angles %s" % mycobot.angles) + +def controller_GUI(): + window = Tkinter.Tk() + window.title("Controller GUI") + window.geometry("480x440") + window.resizable(False, False) + + def apply_cur_scale(value): + global change_list, prev_angles + new_data_list = [float(coord_scale1.get()),float(coord_scale2.get()),float(coord_scale3.get()),float(coord_scale4.get()),float(coord_scale5.get()),float(coord_scale6.get())] + new_data_list = [round(num, 2) for num in new_data_list] + prev_angles = new_data_list + change_list = new_data_list + + # Label Components + coord_label1 = Label(window, text = "joint2_to_joint1") + coord_label1.place(x = 20, y = 20, width = 150, height = 50) + coord_label2 = Label(window, text = "joint3_to_joint2") + coord_label2.place(x = 20, y = 80, width = 150, height = 50) + coord_label3 = Label(window, text = "joint4_to_joint3") + coord_label3.place(x = 20, y = 140, width = 150, height = 50) + coord_label4 = Label(window, text = "joint5_to_joint4") + coord_label4.place(x = 20, y = 200, width = 150, height = 50) + coord_label5 = Label(window, text = "joint6_to_joint5") + coord_label5.place(x = 20, y = 260, width = 150, height = 50) + coord_label6 = Label(window, text = "joint6output_to_joint6") + coord_label6.place(x = 20, y = 320, width = 150, height = 50) + # Entry Components + global coord_entry1, coord_entry2, coord_entry3, coord_entry4, coord_entry5, coord_entry6 + coord_entry1 = Entry(window) + coord_entry1.place(x = 180, y = 30, width = 80, height = 30) + coord_entry2 = Entry(window) + coord_entry2.place(x = 180, y = 90, width = 80, height = 30) + coord_entry3 = Entry(window) + coord_entry3.place(x = 180, y = 150, width = 80, height = 30) + coord_entry4 = Entry(window) + coord_entry4.place(x = 180, y = 210, width = 80, height = 30) + coord_entry5 = Entry(window) + coord_entry5.place(x = 180, y = 270, width = 80, height = 30) + coord_entry6 = Entry(window) + coord_entry6.place(x = 180, y = 330, width = 80, height = 30) + # Scale Components + global coord_scale1, coord_scale2, coord_scale3, coord_scale4, coord_scale5, coord_scale6 + coord_scale1 = Scale(window, orient=HORIZONTAL, from_=-168, to=168, command=apply_cur_scale) + coord_scale1.place(x = 280, y = 20, width = 180, height = 50) + coord_scale2 = Scale(window, orient=HORIZONTAL, from_=-135, to=135, command=apply_cur_scale) + coord_scale2.place(x = 280, y = 80, width = 180, height = 50) + coord_scale3 = Scale(window, orient=HORIZONTAL, from_=-150, to=150, command=apply_cur_scale) + coord_scale3.place(x = 280, y = 140, width = 180, height = 50) + coord_scale4 = Scale(window, orient=HORIZONTAL, from_=-145, to=145, command=apply_cur_scale) + coord_scale4.place(x = 280, y = 200, width = 180, height = 50) + coord_scale5 = Scale(window, orient=HORIZONTAL, from_=-165, to=165, command=apply_cur_scale) + coord_scale5.place(x = 280, y = 260, width = 180, height = 50) + coord_scale6 = Scale(window, orient=HORIZONTAL, from_=-180, to=180, command=apply_cur_scale) + coord_scale6.place(x = 280, y = 320, width = 180, height = 50) + + # Button + change_button = Button(window, command = move_arm, text = "Set Angles") + change_button.place(x = 140, y = 380, width = 200, height = 40) + + window.mainloop() + +if __name__ == "__main__": + controller_thread = threading.Thread(target=controller_GUI) + controller_thread.start() + try: + talker() + except rospy.ROSInterruptException: + pass + controller_thread.join() \ No newline at end of file diff --git a/mycobot_280/mycobot_280_gazebo_moveit/scripts/slider_control.py b/mycobot_280/mycobot_280_gazebo_moveit/scripts/slider_control.py new file mode 100755 index 00000000..fc97d524 --- /dev/null +++ b/mycobot_280/mycobot_280_gazebo_moveit/scripts/slider_control.py @@ -0,0 +1,56 @@ +#!/usr/bin/env python2 +# -*- coding: utf-8 -*- + +"""[summary] +This file obtains the joint angle of the manipulator in ROS, +and then sends it directly to the real manipulator using `pymycobot` API. +This file is [slider_control.launch] related script. +Passable parameters: + port: serial prot string. Defaults is '/dev/ttyUSB0' + baud: serial prot baudrate. Defaults is 115200. +""" +import time +import math +import rospy +from sensor_msgs.msg import JointState + +from pymycobot.mycobot import MyCobot + + +mc = None + + +def callback(data): + # rospy.loginfo(rospy.get_caller_id() + "%s", data.position) + + data_list = [] + for index, value in enumerate(data.position): + radians_to_angles = round(math.degrees(value), 2) + data_list.append(radians_to_angles) + + rospy.loginfo(rospy.get_caller_id() + "%s", data_list) + mc.send_angles(data_list, 25) + # mc.get_system_version() + + +def listener(): + global mc + rospy.init_node("control_slider", anonymous=True) + + rospy.Subscriber("joint_states", JointState, callback) + port = rospy.get_param("~port", "/dev/ttyUSB0") + baud = rospy.get_param("~baud", 115200) + print(port, baud) + mc = MyCobot(port, baud) + time.sleep(0.05) + mc.set_fresh_mode(1) + time.sleep(0.05) + + # spin() simply keeps python from exiting until this node is stopped + # spin()只是阻止python退出,直到该节点停止 + print("spin ...") + rospy.spin() + + +if __name__ == "__main__": + listener() diff --git a/mycobot_280/mycobot_280_gazebo_moveit/scripts/slider_control_gazebo.py b/mycobot_280/mycobot_280_gazebo_moveit/scripts/slider_control_gazebo.py new file mode 100755 index 00000000..64e1b997 --- /dev/null +++ b/mycobot_280/mycobot_280_gazebo_moveit/scripts/slider_control_gazebo.py @@ -0,0 +1,66 @@ +#!/usr/bin/env python2 +# -*- coding: utf-8 -*- + +"""[summary] +This file obtains the joint angle of the manipulator in ROS, +and then sends it directly to the real manipulator using `pymycobot` API. +This file is [slider_control.launch] related script. +Passable parameters: + port: serial prot string. Defaults is '/dev/ttyUSB0' + baud: serial prot baudrate. Defaults is 115200. +""" +import time +import math +import rospy +from sensor_msgs.msg import JointState +from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint +from pymycobot.mycobot import MyCobot +import copy + +mc, pub_command = None, None + +def callback(data): + # rospy.loginfo(rospy.get_caller_id() + "%s", data.position) + data_list = [] + for index, value in enumerate(data.position): + radians_to_angles = round(math.degrees(value), 2) + data_list.append(radians_to_angles) + + joint_trajectory = JointTrajectory() + joint_trajectory.header.stamp = rospy.Time.now() + joint_trajectory.joint_names = ["joint2_to_joint1","joint3_to_joint2","joint4_to_joint3","joint5_to_joint4","joint6_to_joint5","joint6output_to_joint6"] + + point = JointTrajectoryPoint() + point.positions = data.position + point.velocities = [0.0] * len(joint_trajectory.joint_names) + point.time_from_start = rospy.Duration(0.5) + joint_trajectory.points.append(point) + + pub_command.publish(joint_trajectory) # Publish the joint trajectory + mc.send_angles(data_list, 25) + # rospy.loginfo(rospy.get_caller_id() + "%s", data_list) + +def listener(): + global mc, pub_command + + rospy.init_node("control_slider", anonymous=True) + + port = rospy.get_param("~port", "/dev/ttyUSB0") + baud = rospy.get_param("~baud", 115200) + print(port, baud) + mc = MyCobot(port, baud) + + pub_command = rospy.Publisher("/mycobot_position_controller/command", JointTrajectory, queue_size=10) + rospy.Subscriber("/joint_states", JointState, callback) + + time.sleep(0.05) + mc.set_fresh_mode(1) + time.sleep(0.05) + + # spin() simply keeps python from exiting until this node is stopped + # spin()只是阻止python退出,直到该节点停止 + print("spin ...") + rospy.spin() + +if __name__ == "__main__": + listener() \ No newline at end of file diff --git a/mycobot_description/urdf/mycobot/mycobot_280_m5_gazebo.urdf b/mycobot_description/urdf/mycobot/mycobot_280_m5_gazebo.urdf new file mode 100644 index 00000000..af6ce500 --- /dev/null +++ b/mycobot_description/urdf/mycobot/mycobot_280_m5_gazebo.urdf @@ -0,0 +1,323 @@ + + + + + + + + + + + + + + + + + true + + + + + + + + + + + + + + + + + true + + + + + + + + + + + + + + + + + + + + true + + + + + + + + + + + + + + + + + + + + true + + + + + + + + + + + + + + + + + + + + true + + + + + + + + + + + + + + + + + + + + true + + + + + + + + + + + + + + + + + + + + true + + + + + + + + + + + + + + + + + + + + true + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + transmission_interface/SimpleTransmission + + + hardware_interface/PositionJointInterface + + + hardware_interface/PositionJointInterface + + 1 + + + + transmission_interface/SimpleTransmission + + + hardware_interface/PositionJointInterface + + + hardware_interface/PositionJointInterface + + 1 + + + + transmission_interface/SimpleTransmission + + + hardware_interface/PositionJointInterface + + + hardware_interface/PositionJointInterface + + 1 + + + + transmission_interface/SimpleTransmission + + + hardware_interface/PositionJointInterface + + + hardware_interface/PositionJointInterface + + 1 + + + + transmission_interface/SimpleTransmission + + + hardware_interface/PositionJointInterface + + + hardware_interface/PositionJointInterface + + 1 + + + + transmission_interface/SimpleTransmission + + + hardware_interface/PositionJointInterface + + + hardware_interface/PositionJointInterface + + 1 + + + + + / + + + + + true + + + true + + + true + + + true + + + true + + + true + + + true + + + true + + \ No newline at end of file