├── .gitignore ├── .gitmodules ├── .travis.yml ├── CMakeLists.txt ├── Docker ├── Dockerfile ├── README.md ├── entrypoint.sh └── slrbot_docker.sh ├── README.md ├── README_ur.md ├── arm_hand_capture ├── CMakeLists.txt ├── README.md ├── launch │ ├── load_camera.launch │ ├── load_camera_uvc.launch │ ├── load_vrpn.launch │ ├── start_all.launch │ ├── start_all_with_image.launch │ ├── start_camera.launch │ ├── start_yumi_teleop.launch │ ├── test_message_filters.launch │ ├── validate_local_frame_transforms.launch │ ├── visualize_recorded_movements.launch │ └── visualize_recorded_movements_README ├── msg │ ├── DualArmDualHandState.msg │ ├── DualArmDualHandStateWithImage.msg │ └── GloveState.msg ├── package.xml ├── rviz │ ├── mocap_tf.rviz │ └── mocap_tf_original_adjusted.rviz ├── script │ ├── bath_process.py │ ├── extract_calibration_data.py │ ├── extract_from_rosbag.py │ ├── grasp_hand.bag │ ├── read_vids.py │ └── swing_arm.bag └── src │ ├── load_adjusted_visualization_markers.cpp │ ├── load_original_visualization_markers.cpp │ ├── load_visualization_markers.cpp │ ├── load_visualization_markers_after_transform.cpp │ ├── load_visualization_markers_before_transform.cpp │ ├── load_visualization_markers_without_image.cpp │ ├── sync_message_topic.cpp │ ├── sync_state_with_image.cpp │ ├── sync_state_without_image.cpp │ ├── synced_message_to_ur5.cpp │ ├── synced_message_to_yumi.cpp │ ├── test_message_filter.cpp │ ├── test_message_filter_class.cpp │ ├── topic_to_sync_1.cpp │ ├── topic_to_sync_2.cpp │ ├── topic_to_sync_3.cpp │ ├── unpack_adjusted_movement_message.cpp │ ├── unpack_movement_after_transform.cpp │ ├── unpack_movement_before_transform.cpp │ ├── unpack_original_movement_message.cpp │ ├── unpack_synced_message.cpp │ ├── unpack_synced_message_with_image.cpp │ ├── unpack_synced_message_without_image.cpp │ ├── validate_local_frame_transforms.cpp │ └── visualize_recorded_movements.cpp ├── arm_hand_retargeting ├── CMakeLists.txt ├── README ├── include │ ├── config.h │ ├── edges │ │ ├── CollisionConstraint.h │ │ ├── DMPConstraints.h │ │ ├── MyUnaryConstraints.h │ │ ├── SmoothnessConstraint.h │ │ └── TrackingConstraint.h │ ├── nullspace_liweijie │ │ ├── NullSpaceControl.h │ │ ├── config_nullspace.h │ │ ├── inverseKinematics.h │ │ ├── kinematics.h │ │ ├── static_matrix_config.h │ │ └── transform_matrix_helper.h │ ├── tools │ │ ├── KDL_FK_Solver.h │ │ ├── collision_checking.h │ │ ├── collision_checking_yumi.h │ │ ├── distance_computation.h │ │ ├── generate_trajectory_from_viewpoints.h │ │ ├── generate_trajectory_using_DMP.h │ │ ├── h5_io.h │ │ └── similarity_network_pytorch.h │ ├── vertices │ │ ├── DMPStartsGoalsVertex.h │ │ └── DualArmDualHandVertex.h │ └── yumi_arm_retarget_g2o_similarity.h ├── launch │ ├── display_human_hand_model.launch │ └── upload_both_hands.launch ├── package.xml ├── rviz │ └── urdf.rviz ├── src │ ├── collision_checking_yumi.cpp │ ├── generate_trajectory_using_DMP.cpp │ ├── obsolete │ │ ├── ur5_arm_retarget_nlopt.cpp │ │ ├── yumi_arm_retarget_g2o.cpp │ │ └── yumi_arm_retarget_nlopt.cpp │ ├── tools │ │ ├── KDL_FK_Solver.cpp │ │ ├── TEST_collision_checking.cpp │ │ ├── TEST_similarity_network_pytorch.cpp │ │ ├── collision_checking.cpp │ │ ├── distance_computation.cpp │ │ ├── generate_trajectory_from_viewpoints.cpp │ │ └── similarity_network_pytorch.cpp │ ├── yumi_arm_retarget_g2o_similarity.cpp │ └── yumi_arm_retarget_hujin_nlopt.cpp └── urdf │ ├── human_hand_model.urdf │ ├── human_hand_model.urdf.xacro │ ├── upload_both_hands.urdf │ ├── upload_both_hands.urdf.xacro │ └── upload_one_hand.urdf.xacro ├── doc └── Doxyfile ├── dual_ur5_control ├── CMakeLists.txt ├── flash model │ ├── flash.SLDASM │ ├── flash_body.SLDPRT │ ├── flash_body.STL │ ├── flash_body_final.STL │ ├── flash_body_new.STL │ ├── flash_body_new_bottom_middle.STL │ ├── flash_body_new_middle.STL │ ├── flash_body_new_middle_other_direction.STL │ ├── flash_body_realign.SLDPRT │ ├── flash_body_realign.STL │ ├── flash_body_realign_frame1.STL │ ├── flash_body_realign_frame1_new.STL │ ├── flash_body_realign_frame2.STL │ ├── flash_body_realign_frame3.STL │ ├── flash_hat.SLDPRT │ ├── flash_hat.STL │ ├── flash_hat_align.STL │ ├── flash_hat_final.STL │ └── ~$flash_body.SLDPRT ├── launch │ └── compare_TP_methods.launch ├── meshes │ ├── flash_body.STL │ ├── flash_body_final.STL │ ├── flash_body_new.STL │ ├── flash_body_new_middle_other_direction.STL │ ├── flash_body_realign.STL │ ├── flash_body_realign_frame1_new.STL │ ├── flash_hat.STL │ └── flash_hat_final.STL ├── package.xml ├── script │ ├── TOPPRA_service.py │ ├── TOPP_service.py │ ├── arm_follow_joint_trajectory.py │ ├── arm_follow_joint_trajectory_tmp.py │ ├── backup │ │ ├── dual_ur5_joint_trajectory.h5 │ │ ├── dual_ur5_joint_trajectory_diff_start_pose_same_goal_pose.h5 │ │ ├── dual_ur5_joint_trajectory_diff_start_same_goal.h5 │ │ ├── dual_ur5_joint_trajectory_diff_start_same_goal_new.h5 │ │ ├── dual_ur5_joint_trajectory_same_start_diff_goal.h5 │ │ └── dual_ur5_joint_trajectory_same_start_goal.h5 │ ├── compare_TP_methods.py │ ├── compare_tp_result.py │ ├── dual_traj_record.xls │ ├── dual_traj_record_diff_start_same_goal.xls │ ├── dual_traj_record_diff_start_same_goal_new.xls │ ├── dual_traj_record_same_start_diff_goal.xls │ ├── dual_traj_record_same_start_goal.xls │ ├── dual_ur5_addTP_concatenate.py │ ├── dual_ur5_compare_diff_TP.py │ ├── dual_ur5_concatenate.py │ ├── dual_ur5_execute_motion.py │ ├── dual_ur5_joint_trajectory.h5 │ ├── dual_ur5_joint_trajectory_DIFF_TIME_PARAMETERIZATION.h5 │ ├── dual_ur5_joint_trajectory_diff_start_pose_same_goal_pose.h5 │ ├── dual_ur5_joint_trajectory_diff_start_same_goal.h5 │ ├── dual_ur5_joint_trajectory_diff_start_same_goal_new.h5 │ ├── dual_ur5_joint_trajectory_same_start_diff_goal.h5 │ ├── dual_ur5_joint_trajectory_same_start_goal.h5 │ ├── dual_ur5_motion.py │ ├── dual_ur5_optim_pso.py │ ├── dual_ur5_whole_cart_traj_concat_2_no_delay.h5 │ ├── dual_ur5_whole_cart_traj_concat_2_with_delay.h5 │ ├── dual_ur5_whole_traj_concat_2(using plan_go really slow).h5 │ ├── example_paths_for_TP_comparison.h5 │ ├── gripper_effort_control.py │ ├── maxVelocity.txt │ ├── process_polish_path.py │ ├── pyswarms_example.py │ ├── report.log │ ├── simple_GD.py │ ├── simple_PSO.py │ ├── test_fk_server.py │ ├── tmp_new_paths_from_primitives.h5 │ ├── traj_pair_lr_9-TOTG.png │ ├── traj_pair_lr_9-ori.png │ └── trajectory.txt ├── sdf │ └── flash_body │ │ ├── meshes │ │ └── flash_body.STL │ │ ├── model.config │ │ └── model.sdf ├── src │ ├── apply_fk_server.cpp │ ├── compute_cartesian_path_server.cpp │ └── fk.cpp └── srv │ ├── CartToJnt.srv │ └── JntToCart.srv ├── dual_ur5_moveit_config ├── .setup_assistant ├── CMakeLists.txt ├── config │ ├── chomp_planning.yaml │ ├── controllers.yaml │ ├── fake_controllers.yaml │ ├── joint_limits.yaml │ ├── kinematics.yaml │ ├── ompl_planning.yaml │ ├── ros_controllers.yaml │ ├── sensors_3d.yaml │ └── ur5.srdf ├── launch │ ├── chomp_planning_pipeline.launch.xml │ ├── default_warehouse_db.launch │ ├── demo.launch │ ├── dual_ur5_arm_bringup_moveit.launch │ ├── dual_ur5_moveit_controller_manager.launch │ ├── fake_moveit_controller_manager.launch │ ├── joystick_control.launch │ ├── move_group.launch │ ├── moveit.rviz │ ├── moveit_rviz.launch │ ├── ompl_planning_pipeline.launch.xml │ ├── planning_context.launch │ ├── planning_pipeline.launch.xml │ ├── ros_controllers.launch │ ├── run_benchmark_ompl.launch │ ├── sensor_manager.launch.xml │ ├── setup_assistant.launch │ ├── trajectory_execution.launch.xml │ ├── ur5_moveit_sensor_manager.launch.xml │ ├── warehouse.launch │ └── warehouse_settings.launch.xml └── package.xml ├── dynamic_mapping_params ├── CMakeLists.txt ├── cfg │ └── MappingParams.cfg ├── msg │ └── MappingParams.msg ├── package.xml └── src │ └── dynamic_reconfigure_node.cpp ├── human_model ├── CMakeLists.txt ├── config │ └── controllers.yaml ├── launch │ └── human_model_visualization.launch ├── meshes │ ├── forearm.dae │ ├── forearm_backup.dae │ ├── hand.dae │ ├── hand_backup.dae │ ├── upperarm.dae │ └── upperarm_backup.dae ├── package.xml ├── rviz │ └── human_model.rviz ├── script │ └── visualize_human_ik_results.py └── urdf │ ├── arm.urdf.xacro │ ├── human_model.gv │ ├── human_model.pdf │ ├── human_model.urdf │ └── human_model.urdf.xacro ├── human_model_moveit_config ├── .setup_assistant ├── CMakeLists.txt ├── config │ ├── chomp_planning.yaml │ ├── fake_controllers.yaml │ ├── human_model.srdf │ ├── joint_limits.yaml │ ├── kinematics.yaml │ ├── ompl_planning.yaml │ ├── ros_controllers.yaml │ └── sensors_3d.yaml ├── launch │ ├── chomp_planning_pipeline.launch.xml │ ├── default_warehouse_db.launch │ ├── demo.launch │ ├── demo_gazebo.launch │ ├── fake_moveit_controller_manager.launch.xml │ ├── gazebo.launch │ ├── human_model_moveit_controller_manager.launch.xml │ ├── human_model_moveit_sensor_manager.launch.xml │ ├── joystick_control.launch │ ├── move_group.launch │ ├── moveit.rviz │ ├── moveit_rviz.launch │ ├── ompl_planning_pipeline.launch.xml │ ├── planning_context.launch │ ├── planning_pipeline.launch.xml │ ├── ros_controllers.launch │ ├── run_benchmark_ompl.launch │ ├── sensor_manager.launch.xml │ ├── setup_assistant.launch │ ├── trajectory_execution.launch.xml │ ├── warehouse.launch │ └── warehouse_settings.launch.xml └── package.xml ├── inspire_hand_description ├── CMakeLists.txt ├── config │ ├── joint_names_left.yaml │ └── joint_names_right.yaml ├── launch │ ├── display_left.launch │ ├── display_right.launch │ ├── gazebo_left.launch │ └── gazebo_right.launch ├── meshes │ ├── left │ │ ├── link1.STL │ │ ├── link11.STL │ │ ├── link111.STL │ │ ├── link2.STL │ │ ├── link22.STL │ │ ├── link3.STL │ │ ├── link33.STL │ │ ├── link4.STL │ │ ├── link44.STL │ │ ├── link5.STL │ │ ├── link51.STL │ │ ├── link52.STL │ │ └── link53.STL │ └── right │ │ ├── Link1.STL │ │ ├── Link11.STL │ │ ├── Link111.STL │ │ ├── Link2.STL │ │ ├── Link22.STL │ │ ├── Link3.STL │ │ ├── Link33.STL │ │ ├── Link4.STL │ │ ├── Link44.STL │ │ ├── Link5.STL │ │ ├── Link51.STL │ │ ├── Link52.STL │ │ └── Link53.STL ├── package.xml ├── robots │ ├── inspire_hand_left.urdf │ └── inspire_hand_right.urdf ├── rviz │ ├── urdf_left.rviz │ └── urdf_right.rviz └── urdf.rviz ├── inspire_hand_driver ├── CMakeLists.txt ├── CMakeLists.txt.user ├── include │ └── hand_control.h ├── launch │ └── hand_control.launch ├── package.xml ├── readme.txt ├── src │ ├── hand_control.cpp │ ├── hand_control_client.cpp │ ├── hand_control_lib.cpp │ ├── handcontroltopicpublisher.cpp │ ├── handcontroltopicpublisher1.cpp │ ├── handcontroltopicsubscriber.cpp │ └── handcontroltopicsubscriber1.cpp └── srv │ ├── get_angle_act.srv │ ├── get_angle_set.srv │ ├── get_current.srv │ ├── get_error.srv │ ├── get_force_act.srv │ ├── get_force_set.srv │ ├── get_pos_act.srv │ ├── get_pos_set.srv │ ├── get_status.srv │ ├── get_temp.srv │ ├── set_angle.srv │ ├── set_clear_error.srv │ ├── set_current_limit.srv │ ├── set_default_force.srv │ ├── set_default_speed.srv │ ├── set_force.srv │ ├── set_force_clb.srv │ ├── set_gesture_no.srv │ ├── set_id.srv │ ├── set_pos.srv │ ├── set_redu_ratio.srv │ ├── set_reset_para.srv │ ├── set_save_flash.srv │ ├── set_speed.srv │ └── set_user_def_angle.srv ├── inspire_hand_python_driver ├── handReadme.txt └── inspire_hand.py ├── inspire_right_hand_moveit_config ├── .setup_assistant ├── CMakeLists.txt ├── config │ ├── chomp_planning.yaml │ ├── fake_controllers.yaml │ ├── inspire_hand_right.srdf │ ├── joint_limits.yaml │ ├── kinematics.yaml │ ├── ompl_planning.yaml │ ├── ros_controllers.yaml │ └── sensors_3d.yaml ├── launch │ ├── chomp_planning_pipeline.launch.xml │ ├── default_warehouse_db.launch │ ├── demo.launch │ ├── demo_gazebo.launch │ ├── fake_moveit_controller_manager.launch.xml │ ├── gazebo.launch │ ├── inspire_hand_right_moveit_controller_manager.launch.xml │ ├── inspire_hand_right_moveit_sensor_manager.launch.xml │ ├── joystick_control.launch │ ├── move_group.launch │ ├── moveit.rviz │ ├── moveit_rviz.launch │ ├── ompl_planning_pipeline.launch.xml │ ├── planning_context.launch │ ├── planning_pipeline.launch.xml │ ├── ros_controllers.launch │ ├── run_benchmark_ompl.launch │ ├── sensor_manager.launch.xml │ ├── setup_assistant.launch │ ├── trajectory_execution.launch.xml │ ├── warehouse.launch │ └── warehouse_settings.launch.xml ├── package.xml └── script │ └── inspire_right_hand_execute_motion.py ├── raw_totg ├── CMakeLists.txt ├── package.xml ├── script │ └── test_TOTG_server.py ├── src │ ├── Example.cpp │ ├── Path.cpp │ ├── Path.h │ ├── Test.cpp │ ├── Trajectory.cpp │ ├── Trajectory.h │ ├── add_time_optimal_parameterization_server.cpp │ ├── get_minimum_time_server.cpp │ └── plotTrajectory.m └── srv │ ├── GetMinTime.srv │ └── PathToTraj.srv ├── realtime_motion_retargeting ├── CMakeLists.txt ├── ExecuteNode.py ├── include │ ├── NullSpaceControl.h │ ├── config.h │ ├── h5_io.h │ ├── inverseKinematics.h │ ├── kinematics.h │ ├── static_matrix_config.h │ ├── transform_matrix_helper.h │ ├── util_functions.h │ └── yumi_trac_ik_solver.h ├── launch │ └── realtime_motion_retargeting.launch ├── msg │ ├── ControlMsg.msg │ └── MotionMsg.msg ├── package.xml └── src │ ├── ControllerNode.cpp │ └── DataSamplerNode.cpp ├── sign_language_robot_control ├── CMakeLists.txt ├── launch │ └── display_sign_language_robot.launch ├── package.xml ├── rviz │ └── urdf.rviz ├── script │ ├── fake_elbow_wrist_path_1.h5 │ ├── fake_elbow_wrist_paths.h5 │ ├── ik_results.h5 │ ├── sign-motion-viapoints.xlsx │ ├── sign_robot_control.py │ └── sign_robot_execute_joint_path.py └── src │ ├── collision_computation.cpp │ ├── compute_arm_motion.cpp │ ├── generate_fake_elbow_wrist_path.cpp │ ├── ik_optim_with_kdl.cpp │ ├── mocap_combined_wrist_pos_ori_elbow_pos_paths.h5 │ ├── mocap_paths.h5 │ ├── use_g2o.cpp │ ├── use_hdf5.cpp │ ├── use_nlopt.cpp │ ├── use_nlopt_batch.cpp │ └── use_nlopt_mocap_rot.cpp ├── sign_language_robot_moveit_config ├── .setup_assistant ├── CMakeLists.txt ├── config │ ├── chomp_planning.yaml │ ├── controllers.yaml │ ├── fake_controllers.yaml │ ├── joint_limits.yaml │ ├── kinematics.yaml │ ├── ompl_planning.yaml │ ├── ros_controllers.yaml │ ├── sensors_3d.yaml │ └── ur5.srdf ├── launch │ ├── chomp_planning_pipeline.launch.xml │ ├── default_warehouse_db.launch │ ├── demo.launch │ ├── demo_gazebo.launch │ ├── fake_moveit_controller_manager.launch │ ├── fake_moveit_controller_manager.launch.xml │ ├── gazebo.launch │ ├── joystick_control.launch │ ├── move_group.launch │ ├── moveit.rviz │ ├── moveit_rviz.launch │ ├── ompl_planning_pipeline.launch.xml │ ├── planning_context.launch │ ├── planning_pipeline.launch.xml │ ├── ros_controllers.launch │ ├── run_benchmark_ompl.launch │ ├── sensor_manager.launch.xml │ ├── setup_assistant.launch │ ├── sign_language_robot_bringup_moveit.launch │ ├── sign_language_robot_moveit_controller_manager.launch │ ├── trajectory_execution.launch.xml │ ├── ur5_moveit_controller_manager.launch.xml │ ├── ur5_moveit_sensor_manager.launch.xml │ ├── warehouse.launch │ └── warehouse_settings.launch.xml └── package.xml ├── universal_robot ├── CHANGELOG.rst ├── CMakeLists.txt └── package.xml ├── ur5_moveit_config ├── .setup_assistant ├── CHANGELOG.rst ├── CMakeLists.txt ├── config │ ├── controllers.yaml │ ├── fake_controllers.yaml │ ├── joint_limits.yaml │ ├── kinematics.yaml │ ├── ompl_planning.yaml │ └── ur5.srdf ├── launch │ ├── default_warehouse_db.launch │ ├── demo.launch │ ├── fake_moveit_controller_manager.launch.xml │ ├── move_group.launch │ ├── moveit.rviz │ ├── moveit_rviz.launch │ ├── my_bringup.launch │ ├── ompl_planning_pipeline.launch.xml │ ├── planning_context.launch │ ├── planning_pipeline.launch.xml │ ├── run_benchmark_ompl.launch │ ├── sensor_manager.launch.xml │ ├── setup_assistant.launch │ ├── trajectory_execution.launch.xml │ ├── ur5_moveit_controller_manager.launch.xml │ ├── ur5_moveit_planning_execution.launch │ ├── ur5_moveit_sensor_manager.launch.xml │ ├── warehouse.launch │ └── warehouse_settings.launch.xml ├── package.xml └── tests │ └── moveit_planning_execution.xml ├── ur_description ├── CHANGELOG.rst ├── CMakeLists.txt ├── launch │ ├── dual_ur5_upload.launch │ ├── load_flash.launch │ ├── sign_language_robot_upload.launch │ ├── test.launch │ ├── ur10_upload.launch │ ├── ur3_upload.launch │ └── ur5_upload.launch ├── meshes │ ├── flash_body │ │ ├── meshes │ │ │ ├── flash_body.STL │ │ │ ├── flash_body_final.STL │ │ │ ├── flash_body_realign_frame1.STL │ │ │ ├── flash_body_realign_frame1_new.STL │ │ │ ├── flash_body_realign_frame2.STL │ │ │ └── flash_body_realign_frame3.STL │ │ ├── model.config │ │ └── model.sdf │ ├── flash_hat │ │ ├── meshes │ │ │ └── flash_hat_final.STL │ │ ├── model.config │ │ ├── model.sdf │ │ └── model_test.sdf │ ├── gripper │ │ ├── base.stl │ │ ├── l1.stl │ │ ├── l2.stl │ │ ├── r1.stl │ │ └── r2.stl │ ├── ur10 │ │ ├── collision │ │ │ ├── base.stl │ │ │ ├── forearm.stl │ │ │ ├── shoulder.stl │ │ │ ├── upperarm.stl │ │ │ ├── wrist1.stl │ │ │ ├── wrist2.stl │ │ │ └── wrist3.stl │ │ └── visual │ │ │ ├── base.dae │ │ │ ├── forearm.dae │ │ │ ├── shoulder.dae │ │ │ ├── upperarm.dae │ │ │ ├── wrist1.dae │ │ │ ├── wrist2.dae │ │ │ └── wrist3.dae │ ├── ur3 │ │ ├── collision │ │ │ ├── base.stl │ │ │ ├── forearm.stl │ │ │ ├── shoulder.stl │ │ │ ├── upperarm.stl │ │ │ ├── wrist1.stl │ │ │ ├── wrist2.stl │ │ │ └── wrist3.stl │ │ └── visual │ │ │ ├── base.dae │ │ │ ├── forearm.dae │ │ │ ├── shoulder.dae │ │ │ ├── upperarm.dae │ │ │ ├── wrist1.dae │ │ │ ├── wrist2.dae │ │ │ └── wrist3.dae │ └── ur5 │ │ ├── base_link.STL │ │ ├── collision │ │ ├── base.stl │ │ ├── forearm.stl │ │ ├── shoulder.stl │ │ ├── upperarm.stl │ │ ├── wrist1.stl │ │ ├── wrist2.stl │ │ └── wrist3.stl │ │ └── visual │ │ ├── base.dae │ │ ├── forearm.dae │ │ ├── shoulder.dae │ │ ├── upperarm.dae │ │ ├── wrist1.dae │ │ ├── wrist2.dae │ │ └── wrist3.dae ├── model.pdf ├── package.xml └── urdf │ ├── common.gazebo.xacro │ ├── ur.gazebo.xacro │ ├── ur.transmission.xacro │ ├── ur10.urdf.xacro │ ├── ur10_joint_limited_robot.urdf.xacro │ ├── ur10_robot.urdf.xacro │ ├── ur3.urdf.xacro │ ├── ur3_joint_limited_robot.urdf.xacro │ ├── ur3_robot.urdf.xacro │ ├── ur5.dae │ ├── ur5.gv │ ├── ur5.pdf │ ├── ur5.urdf │ ├── ur5.urdf.xacro │ ├── ur5_joint_limited_robot.urdf.xacro │ ├── ur5_robot.urdf │ ├── ur5_robot.urdf.xacro │ ├── ur5_robot12.urdf │ ├── ur5_robot1232.urdf │ ├── ur5_robot_backup_original_range.urdf │ └── ur5_robot_with_hands.urdf ├── ur_gazebo ├── CHANGELOG.rst ├── CMakeLists.txt ├── controller │ ├── arm_controller_ur10.yaml │ ├── arm_controller_ur3.yaml │ ├── arm_controller_ur5.yaml │ ├── dual_ur5_controller.yaml │ ├── joint_state_controller.yaml │ └── sign_language_robot_controller.yaml ├── launch │ ├── controller_utils.launch │ ├── dual_ur5_arm_world.launch │ ├── sign_language_robot_world.launch │ ├── ur10.launch │ ├── ur10_joint_limited.launch │ ├── ur3.launch │ ├── ur3_joint_limited.launch │ ├── ur5.launch │ └── ur5_joint_limited.launch ├── package.xml └── tests │ └── roslaunch_test.xml ├── ur_modern_driver └── CMakeLists.txt ├── ur_msgs ├── CHANGELOG.rst ├── CMakeLists.txt ├── msg │ ├── Analog.msg │ ├── Digital.msg │ ├── IOStates.msg │ ├── MasterboardDataMsg.msg │ ├── RobotStateRTMsg.msg │ └── ToolDataMsg.msg ├── package.xml └── srv │ ├── SetIO.srv │ └── SetPayload.srv ├── yumi ├── .gitignore ├── README.md ├── gazebo_mimic │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── README.md │ ├── include │ │ └── gazebo_mimic_plugin │ │ │ └── mimic_plugin.h │ ├── package.xml │ └── src │ │ └── gazebo_mimic_plugin │ │ └── mimic_plugin.cpp ├── license.dat ├── yumi_moveit_config │ ├── .setup_assistant │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── config │ │ ├── controllers.yaml │ │ ├── fake_controllers.yaml │ │ ├── joint_limits.yaml │ │ ├── kinematics.yaml │ │ ├── ompl_planning.yaml │ │ └── yumi.srdf │ ├── launch │ │ ├── default_warehouse_db.launch │ │ ├── demo.launch │ │ ├── demo_online.launch │ │ ├── fake_moveit_controller_manager.launch.xml │ │ ├── joystick_control.launch │ │ ├── move_group.launch │ │ ├── moveit.rviz │ │ ├── moveit_rviz.launch │ │ ├── ompl_planning_pipeline.launch.xml │ │ ├── planning_context.launch │ │ ├── planning_pipeline.launch.xml │ │ ├── run_benchmark_ompl.launch │ │ ├── sensor_manager.launch.xml │ │ ├── setup_assistant.launch │ │ ├── trajectory_execution.launch.xml │ │ ├── warehouse.launch │ │ ├── warehouse_settings.launch.xml │ │ ├── yumi_moveit_controller_manager.launch.xml │ │ └── yumi_moveit_sensor_manager.launch.xml │ └── package.xml └── yumi_support │ ├── CHANGELOG.rst │ ├── CMakeLists.txt │ ├── config │ ├── joint_names_left.yaml │ └── joint_names_right.yaml │ ├── launch │ └── robot_interface.launch │ ├── package.xml │ └── rapid │ ├── ROS_common.sys │ ├── ROS_messages.sys │ ├── ROS_motionServer_left.mod │ ├── ROS_motionServer_right.mod │ ├── ROS_motion_left.mod │ ├── ROS_motion_right.mod │ ├── ROS_socket.sys │ ├── ROS_stateServer_left.mod │ └── ROS_stateServer_right.mod ├── yumi_control ├── CMakeLists.txt ├── launch │ ├── display_yumi_robot.launch │ └── display_yumi_with_hands.launch ├── package.xml └── rviz │ ├── urdf.rviz │ └── yumi_with_hands_urdf.rviz ├── yumi_description ├── CHANGELOG.rst ├── CMakeLists.txt ├── README.md ├── meshes │ ├── body.stl │ ├── coarse │ │ ├── .gitignore │ │ ├── body.stl │ │ ├── link_1.stl │ │ ├── link_2.stl │ │ ├── link_3.stl │ │ ├── link_4.stl │ │ ├── link_5.stl │ │ ├── link_6.stl │ │ └── link_7.stl │ ├── gripper │ │ ├── base.stl │ │ ├── coarse │ │ │ ├── base.stl │ │ │ └── finger.stl │ │ └── finger.stl │ ├── link_1.stl │ ├── link_2.stl │ ├── link_3.stl │ ├── link_4.stl │ ├── link_5.stl │ ├── link_6.stl │ └── link_7.stl ├── package.xml ├── urdf │ ├── Gazebo │ │ ├── gazebo.urdf.xacro │ │ └── yumi.gazebo.xacro │ ├── Grippers │ │ ├── yumi_servo_gripper.gazebo.xacro │ │ ├── yumi_servo_gripper.transmission.xacro │ │ └── yumi_servo_gripper.xacro │ ├── Util │ │ ├── materials.xacro │ │ └── utilities.xacro │ ├── yumi.transmission.xacro │ ├── yumi.urdf │ ├── yumi.urdf.xacro │ ├── yumi.xacro │ └── yumi_with_hands.urdf └── yumi.rviz ├── yumi_sign_language_robot_control ├── CMakeLists.txt ├── config │ └── controllers.yaml ├── launch │ └── yumi_control.launch ├── package.xml ├── rviz │ └── yumi_with_inspire_hand.rviz └── script │ ├── yumi_controller_control.py │ ├── yumi_sign_robot_execute_arm_joint_path.py │ ├── yumi_sign_robot_execute_joint_path.py │ ├── yumi_sign_robot_execute_pure_ik_joint_path.py │ └── yumi_sign_robot_track_dmp_trajs.py └── yumi_sign_language_robot_moveit_config ├── .setup_assistant ├── CMakeLists.txt ├── config ├── chomp_planning.yaml ├── fake_controllers.yaml ├── joint_limits.yaml ├── kinematics.yaml ├── ompl_planning.yaml ├── ros_controllers.yaml ├── sensors_3d.yaml └── yumi.srdf ├── launch ├── chomp_planning_pipeline.launch.xml ├── default_warehouse_db.launch ├── demo.launch ├── demo_gazebo.launch ├── fake_moveit_controller_manager.launch.xml ├── gazebo.launch ├── joystick_control.launch ├── move_group.launch ├── moveit.rviz ├── moveit_rviz.launch ├── ompl_planning_pipeline.launch.xml ├── planning_context.launch ├── planning_pipeline.launch.xml ├── ros_controllers.launch ├── run_benchmark_ompl.launch ├── sensor_manager.launch.xml ├── setup_assistant.launch ├── trajectory_execution.launch.xml ├── warehouse.launch ├── warehouse_settings.launch.xml ├── yumi_moveit_controller_manager.launch.xml └── yumi_moveit_sensor_manager.launch.xml └── package.xml /.gitignore: -------------------------------------------------------------------------------- 1 | *~ 2 | *.pyc 3 | *.h5 4 | *.pth 5 | *.pt 6 | *.bag 7 | *.avi 8 | /doc/doxy_docs/ 9 | /.vscode/ 10 | -------------------------------------------------------------------------------- /.gitmodules: -------------------------------------------------------------------------------- 1 | [submodule "dataglove_calib_visual"] 2 | path = dataglove_calib_visual 3 | url = https://github.com/liangyuwei/dataglove_calib_visual 4 | -------------------------------------------------------------------------------- /CMakeLists.txt: -------------------------------------------------------------------------------- 1 | /opt/ros/kinetic/share/catkin/cmake/toplevel.cmake -------------------------------------------------------------------------------- /Docker/entrypoint.sh: -------------------------------------------------------------------------------- 1 | #!/bin/bash 2 | # /etc/profile would be run before **login shell**, which can be used to set environment variables 3 | echo "export DISPLAY=$DISPLAY" >> /etc/profile 4 | echo "export QT_X11_NO_MITSHM=1" >> /etc/profile 5 | exec "$@" -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # sign_language_robot 2 | This is the code for the paper [_"Dynamic Movement Primitive based Motion Retargeting for Dual-Arm Sign Language Motions"_](http://arxiv.org/abs/2011.03914) accepted by ICRA 2021. 3 | 4 | Youtube Video: [_Click Here_](https://www.youtube.com/watch?v=jPvrAsN1Iwk&t=7s) 5 | 6 | Bilibili Video: [_Click Here_](https://www.bilibili.com/video/BV12i4y1K76G/) 7 | 8 | # Structure 9 | This repo contains code for recording and processing sign language demonstrations, motion retargeting, and other stuffs. Will be re-organized soon... 10 | 11 | # About data collection 12 | We use OptiTrack Motive and Wiseglove for recording human arm motions and finger movements. For further details, please refer to ```arm_hand_capture/README.md.``` 13 | 14 | # Dependencies 15 | For data collection: 16 | usb_cam 17 | vrpn_client_ros 18 | rosserial_server 19 | 20 | # FAQ 21 | 1. Error “sh: 1: v4l2-ctl: not found” requires the installation of v4l2, run ```sudo apt-get install v4l-utils``` 22 | -------------------------------------------------------------------------------- /arm_hand_capture/launch/load_camera.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | -------------------------------------------------------------------------------- /arm_hand_capture/launch/load_vrpn.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | server: $(arg server) 8 | port: 3883 9 | 10 | update_frequency: 100.0 11 | frame_id: world 12 | 13 | # Use the VRPN server's time, or the client's ROS time. 14 | use_server_time: false 15 | broadcast_tf: true 16 | 17 | # Must either specify refresh frequency > 0.0, or a list of trackers to create 18 | refresh_tracker_frequency: 1.0 19 | #trackers: 20 | #- FirstTracker 21 | #- SecondTracker 22 | 23 | 24 | 25 | 26 | -------------------------------------------------------------------------------- /arm_hand_capture/launch/test_message_filters.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | -------------------------------------------------------------------------------- /arm_hand_capture/launch/validate_local_frame_transforms.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | -------------------------------------------------------------------------------- /arm_hand_capture/launch/visualize_recorded_movements.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | -------------------------------------------------------------------------------- /arm_hand_capture/launch/visualize_recorded_movements_README: -------------------------------------------------------------------------------- 1 | 1. arm_hand_capture/script/extract_fom_rosbag.py 2 | 3 | Manually set demonstrator hand length to compute left and right hand tip trajectories. 4 | 5 | 6 | 7 | ==> 2. MATLAB, DMP_learn.py 8 | 9 | Manually set robot hand length to compute robot's left and right wrist trajectories from human hand tip trajectories. 10 | 11 | 12 | 13 | ==> 3. arm_hand_capture/src/load_{adjusted/original}_visualization_markers.cpp 14 | 15 | Manually set demonstrator's and robot's hand length respectively, so as to set up appropriate markers for both hands. 16 | Note that here the data should be inconsistent with the data used above, since here we won't load them from h5 file. 17 | 18 | 19 | 20 | ==> 4. roslaunch arm_hand_capture visualize_recorder_movements.launch to open RViz, waiting for visualization_marks message and tf transform 21 | 22 | 23 | 24 | 25 | ==> 5. Run visualize_recorded_movements node to read selected movements from h5 file, and generate corresponding state message, for RViz to receive and display. 26 | -------------------------------------------------------------------------------- /arm_hand_capture/msg/DualArmDualHandState.msg: -------------------------------------------------------------------------------- 1 | # A representation describing the state of both hands and both arms, at the same time instance sync-ed by message_filters' Approximate Time Synchronization policy. 2 | 3 | # Left arm and left hand 4 | geometry_msgs/PoseStamped left_upperarm_pose 5 | geometry_msgs/PoseStamped left_forearm_pose 6 | geometry_msgs/PoseStamped left_hand_pose 7 | # arm_hand_capture/GloveState left_glove_state 8 | 9 | # Right arm and right hand 10 | geometry_msgs/PoseStamped right_upperarm_pose 11 | geometry_msgs/PoseStamped right_forearm_pose 12 | geometry_msgs/PoseStamped right_hand_pose 13 | arm_hand_capture/GloveState glove_state 14 | -------------------------------------------------------------------------------- /arm_hand_capture/msg/DualArmDualHandStateWithImage.msg: -------------------------------------------------------------------------------- 1 | # A message type combined with arm-hand state and the corresponding image frame. 2 | # Note that message_filters can only work with messages that have Headers!!! 3 | 4 | # Left arm and left hand 5 | geometry_msgs/PoseStamped left_upperarm_pose 6 | geometry_msgs/PoseStamped left_forearm_pose 7 | geometry_msgs/PoseStamped left_hand_pose 8 | arm_hand_capture/GloveState left_glove_state 9 | 10 | # Right arm and right hand 11 | geometry_msgs/PoseStamped right_upperarm_pose 12 | geometry_msgs/PoseStamped right_forearm_pose 13 | geometry_msgs/PoseStamped right_hand_pose 14 | arm_hand_capture/GloveState glove_state 15 | 16 | # Corresponding image 17 | sensor_msgs/Image image 18 | 19 | -------------------------------------------------------------------------------- /arm_hand_capture/msg/GloveState.msg: -------------------------------------------------------------------------------- 1 | std_msgs/Header header 2 | float64[] left_glove_state 3 | float64[] right_glove_state 4 | uint64[] l_glove_elec 5 | uint64[] r_glove_elec 6 | -------------------------------------------------------------------------------- /arm_hand_capture/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | arm_hand_capture 4 | 0.0.0 5 | The arm_hand_capture package 6 | 7 | 8 | 9 | 10 | liangyuwei 11 | 12 | 13 | 14 | 15 | 16 | TODO 17 | 18 | 19 | catkin 20 | 21 | message_generation 22 | 23 | 24 | message_runtime 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | -------------------------------------------------------------------------------- /arm_hand_capture/script/grasp_hand.bag: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/arm_hand_capture/script/grasp_hand.bag -------------------------------------------------------------------------------- /arm_hand_capture/script/swing_arm.bag: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/arm_hand_capture/script/swing_arm.bag -------------------------------------------------------------------------------- /arm_hand_capture/src/topic_to_sync_1.cpp: -------------------------------------------------------------------------------- 1 | #include "ros/ros.h" 2 | #include "geometry_msgs/PoseStamped.h" 3 | #include "ros/time.h" 4 | 5 | 6 | int main(int argc, char **argv) 7 | { 8 | 9 | 10 | ros::init(argc, argv, "topic_to_syn_1_node"); 11 | 12 | ros::NodeHandle n; 13 | 14 | ros::Publisher pub = n.advertise("topic_to_sync_1", 1000); 15 | 16 | ros::Rate loop_rate(10); // sleep enough time(leftover) to hit 10Hz publish rate 17 | 18 | 19 | int count = 0; 20 | while (ros::ok()) 21 | { 22 | // Set up the message content 23 | geometry_msgs::PoseStamped pose; 24 | 25 | pose.header.stamp = ros::Time::now(); // add timestamp 26 | pose.pose.position.x = (double)count; // specify position 27 | 28 | //ROS_INFO("%s", msg.data.c_str()); 29 | 30 | // Publish the message 31 | pub.publish(pose); 32 | 33 | ros::spinOnce(); 34 | 35 | loop_rate.sleep(); // sleep through the leftover time to hit 10Hz publish rate 36 | ++count; 37 | } 38 | 39 | 40 | return 0; 41 | } 42 | -------------------------------------------------------------------------------- /arm_hand_capture/src/topic_to_sync_2.cpp: -------------------------------------------------------------------------------- 1 | #include "ros/ros.h" 2 | #include "geometry_msgs/PoseStamped.h" 3 | #include "ros/time.h" 4 | 5 | 6 | int main(int argc, char **argv) 7 | { 8 | 9 | ros::init(argc, argv, "topic_to_syn_2_node"); 10 | 11 | ros::NodeHandle n; 12 | 13 | 14 | ros::Publisher pub = n.advertise("topic_to_sync_2", 1000); 15 | 16 | ros::Rate loop_rate(1); // sleep enough time(leftover) to hit 10Hz publish rate 17 | 18 | 19 | int count = 0; 20 | while (ros::ok()) 21 | { 22 | // Set up the message content 23 | geometry_msgs::PoseStamped pose; 24 | 25 | pose.header.stamp = ros::Time::now(); // add timestamp 26 | pose.pose.position.y = (double)count; // specify position 27 | 28 | //ROS_INFO("%s", msg.data.c_str()); 29 | 30 | // Publish the message 31 | pub.publish(pose); 32 | 33 | ros::spinOnce(); 34 | 35 | loop_rate.sleep(); // sleep through the leftover time to hit 10Hz publish rate 36 | ++count; 37 | } 38 | 39 | 40 | return 0; 41 | } 42 | -------------------------------------------------------------------------------- /arm_hand_capture/src/topic_to_sync_3.cpp: -------------------------------------------------------------------------------- 1 | #include "ros/ros.h" 2 | #include "geometry_msgs/PoseStamped.h" 3 | #include "ros/time.h" 4 | 5 | 6 | int main(int argc, char **argv) 7 | { 8 | 9 | ros::init(argc, argv, "topic_to_syn_3_node"); 10 | 11 | ros::NodeHandle n; 12 | 13 | 14 | ros::Publisher pub = n.advertise("topic_to_sync_3", 1000); 15 | 16 | ros::Rate loop_rate(5); // sleep enough time(leftover) to hit 10Hz publish rate 17 | 18 | 19 | int count = 0; 20 | while (ros::ok()) 21 | { 22 | // Set up the message content 23 | geometry_msgs::PoseStamped pose; 24 | 25 | pose.header.stamp = ros::Time::now(); // add timestamp 26 | pose.pose.position.z = (double)count; // specify position 27 | 28 | //ROS_INFO("%s", msg.data.c_str()); 29 | 30 | // Publish the message 31 | pub.publish(pose); 32 | 33 | ros::spinOnce(); 34 | 35 | loop_rate.sleep(); // sleep through the leftover time to hit 10Hz publish rate 36 | ++count; 37 | } 38 | 39 | 40 | return 0; 41 | } 42 | -------------------------------------------------------------------------------- /arm_hand_retargeting/README: -------------------------------------------------------------------------------- 1 | 1. Use libTorch with catkin_make(ros) 2 | 3 | 4 | *(1)* Use pre-built cxx11 ABI: 5 | https://pytorch.org/get-started/locally/, choose LibTorch, download Pre-cxx11 ABI, extract to ~/libtorch. 6 | 7 | 8 | *(2)* The above ABI requires cudNN to be installed: 9 | Download corresponding version on https://developer.nvidia.com/rdp/cudnn-archive, choose .tgz !!! 10 | 11 | tar -zxvf cudnn.tgz 12 | 13 | sudo cp ./include/cudnn.h /usr/local/cuda-10.2/include 14 | 15 | sudo cp ./lib64/libcudnn* /usr/local/cuda-10.2/lib64 16 | 17 | sudo chmod a+r /usr/local/cuda-10.2/include/cudnn.h /usr/local/cuda-10.2/lib64/libcudnn* 18 | 19 | 20 | *(3)* 21 | 22 | 23 | 24 | * Actually, I didn't fix the linking error - undefined reference to symbol 'GOMP_parallel@@GOMP_4.0 - because I don't know why... 25 | All I did is just linking torch_libraries with hdf5_libraries ahead of linking tmp_torch to the g2o retargeting code.. and it worked... 26 | 27 | 28 | 29 | 30 | 31 | 32 | -------------------------------------------------------------------------------- /arm_hand_retargeting/launch/display_human_hand_model.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | -------------------------------------------------------------------------------- /arm_hand_retargeting/launch/upload_both_hands.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | -------------------------------------------------------------------------------- /arm_hand_retargeting/urdf/upload_both_hands.urdf.xacro: -------------------------------------------------------------------------------- 1 | 2 | 3 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | -------------------------------------------------------------------------------- /arm_hand_retargeting/urdf/upload_one_hand.urdf.xacro: -------------------------------------------------------------------------------- 1 | 2 | 3 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | -------------------------------------------------------------------------------- /dual_ur5_control/flash model/flash.SLDASM: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/dual_ur5_control/flash model/flash.SLDASM -------------------------------------------------------------------------------- /dual_ur5_control/flash model/flash_body.SLDPRT: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/dual_ur5_control/flash model/flash_body.SLDPRT -------------------------------------------------------------------------------- /dual_ur5_control/flash model/flash_body.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/dual_ur5_control/flash model/flash_body.STL -------------------------------------------------------------------------------- /dual_ur5_control/flash model/flash_body_final.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/dual_ur5_control/flash model/flash_body_final.STL -------------------------------------------------------------------------------- /dual_ur5_control/flash model/flash_body_new.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/dual_ur5_control/flash model/flash_body_new.STL -------------------------------------------------------------------------------- /dual_ur5_control/flash model/flash_body_new_bottom_middle.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/dual_ur5_control/flash model/flash_body_new_bottom_middle.STL -------------------------------------------------------------------------------- /dual_ur5_control/flash model/flash_body_new_middle.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/dual_ur5_control/flash model/flash_body_new_middle.STL -------------------------------------------------------------------------------- /dual_ur5_control/flash model/flash_body_new_middle_other_direction.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/dual_ur5_control/flash model/flash_body_new_middle_other_direction.STL -------------------------------------------------------------------------------- /dual_ur5_control/flash model/flash_body_realign.SLDPRT: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/dual_ur5_control/flash model/flash_body_realign.SLDPRT -------------------------------------------------------------------------------- /dual_ur5_control/flash model/flash_body_realign.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/dual_ur5_control/flash model/flash_body_realign.STL -------------------------------------------------------------------------------- /dual_ur5_control/flash model/flash_body_realign_frame1.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/dual_ur5_control/flash model/flash_body_realign_frame1.STL -------------------------------------------------------------------------------- /dual_ur5_control/flash model/flash_body_realign_frame1_new.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/dual_ur5_control/flash model/flash_body_realign_frame1_new.STL -------------------------------------------------------------------------------- /dual_ur5_control/flash model/flash_body_realign_frame2.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/dual_ur5_control/flash model/flash_body_realign_frame2.STL -------------------------------------------------------------------------------- /dual_ur5_control/flash model/flash_body_realign_frame3.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/dual_ur5_control/flash model/flash_body_realign_frame3.STL -------------------------------------------------------------------------------- /dual_ur5_control/flash model/flash_hat.SLDPRT: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/dual_ur5_control/flash model/flash_hat.SLDPRT -------------------------------------------------------------------------------- /dual_ur5_control/flash model/flash_hat.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/dual_ur5_control/flash model/flash_hat.STL -------------------------------------------------------------------------------- /dual_ur5_control/flash model/flash_hat_align.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/dual_ur5_control/flash model/flash_hat_align.STL -------------------------------------------------------------------------------- /dual_ur5_control/flash model/flash_hat_final.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/dual_ur5_control/flash model/flash_hat_final.STL -------------------------------------------------------------------------------- /dual_ur5_control/flash model/~$flash_body.SLDPRT: -------------------------------------------------------------------------------- 1 | Liangyuwei -------------------------------------------------------------------------------- /dual_ur5_control/launch/compare_TP_methods.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | -------------------------------------------------------------------------------- /dual_ur5_control/meshes/flash_body.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/dual_ur5_control/meshes/flash_body.STL -------------------------------------------------------------------------------- /dual_ur5_control/meshes/flash_body_final.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/dual_ur5_control/meshes/flash_body_final.STL -------------------------------------------------------------------------------- /dual_ur5_control/meshes/flash_body_new.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/dual_ur5_control/meshes/flash_body_new.STL -------------------------------------------------------------------------------- /dual_ur5_control/meshes/flash_body_new_middle_other_direction.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/dual_ur5_control/meshes/flash_body_new_middle_other_direction.STL -------------------------------------------------------------------------------- /dual_ur5_control/meshes/flash_body_realign.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/dual_ur5_control/meshes/flash_body_realign.STL -------------------------------------------------------------------------------- /dual_ur5_control/meshes/flash_body_realign_frame1_new.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/dual_ur5_control/meshes/flash_body_realign_frame1_new.STL -------------------------------------------------------------------------------- /dual_ur5_control/meshes/flash_hat.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/dual_ur5_control/meshes/flash_hat.STL -------------------------------------------------------------------------------- /dual_ur5_control/meshes/flash_hat_final.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/dual_ur5_control/meshes/flash_hat_final.STL -------------------------------------------------------------------------------- /dual_ur5_control/script/backup/dual_ur5_joint_trajectory.h5: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/dual_ur5_control/script/backup/dual_ur5_joint_trajectory.h5 -------------------------------------------------------------------------------- /dual_ur5_control/script/backup/dual_ur5_joint_trajectory_diff_start_pose_same_goal_pose.h5: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/dual_ur5_control/script/backup/dual_ur5_joint_trajectory_diff_start_pose_same_goal_pose.h5 -------------------------------------------------------------------------------- /dual_ur5_control/script/backup/dual_ur5_joint_trajectory_diff_start_same_goal.h5: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/dual_ur5_control/script/backup/dual_ur5_joint_trajectory_diff_start_same_goal.h5 -------------------------------------------------------------------------------- /dual_ur5_control/script/backup/dual_ur5_joint_trajectory_diff_start_same_goal_new.h5: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/dual_ur5_control/script/backup/dual_ur5_joint_trajectory_diff_start_same_goal_new.h5 -------------------------------------------------------------------------------- /dual_ur5_control/script/backup/dual_ur5_joint_trajectory_same_start_diff_goal.h5: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/dual_ur5_control/script/backup/dual_ur5_joint_trajectory_same_start_diff_goal.h5 -------------------------------------------------------------------------------- /dual_ur5_control/script/backup/dual_ur5_joint_trajectory_same_start_goal.h5: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/dual_ur5_control/script/backup/dual_ur5_joint_trajectory_same_start_goal.h5 -------------------------------------------------------------------------------- /dual_ur5_control/script/dual_traj_record.xls: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/dual_ur5_control/script/dual_traj_record.xls -------------------------------------------------------------------------------- /dual_ur5_control/script/dual_traj_record_diff_start_same_goal.xls: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/dual_ur5_control/script/dual_traj_record_diff_start_same_goal.xls -------------------------------------------------------------------------------- /dual_ur5_control/script/dual_traj_record_diff_start_same_goal_new.xls: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/dual_ur5_control/script/dual_traj_record_diff_start_same_goal_new.xls -------------------------------------------------------------------------------- /dual_ur5_control/script/dual_traj_record_same_start_diff_goal.xls: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/dual_ur5_control/script/dual_traj_record_same_start_diff_goal.xls -------------------------------------------------------------------------------- /dual_ur5_control/script/dual_traj_record_same_start_goal.xls: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/dual_ur5_control/script/dual_traj_record_same_start_goal.xls -------------------------------------------------------------------------------- /dual_ur5_control/script/dual_ur5_joint_trajectory.h5: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/dual_ur5_control/script/dual_ur5_joint_trajectory.h5 -------------------------------------------------------------------------------- /dual_ur5_control/script/dual_ur5_joint_trajectory_DIFF_TIME_PARAMETERIZATION.h5: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/dual_ur5_control/script/dual_ur5_joint_trajectory_DIFF_TIME_PARAMETERIZATION.h5 -------------------------------------------------------------------------------- /dual_ur5_control/script/dual_ur5_joint_trajectory_diff_start_pose_same_goal_pose.h5: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/dual_ur5_control/script/dual_ur5_joint_trajectory_diff_start_pose_same_goal_pose.h5 -------------------------------------------------------------------------------- /dual_ur5_control/script/dual_ur5_joint_trajectory_diff_start_same_goal.h5: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/dual_ur5_control/script/dual_ur5_joint_trajectory_diff_start_same_goal.h5 -------------------------------------------------------------------------------- /dual_ur5_control/script/dual_ur5_joint_trajectory_diff_start_same_goal_new.h5: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/dual_ur5_control/script/dual_ur5_joint_trajectory_diff_start_same_goal_new.h5 -------------------------------------------------------------------------------- /dual_ur5_control/script/dual_ur5_joint_trajectory_same_start_diff_goal.h5: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/dual_ur5_control/script/dual_ur5_joint_trajectory_same_start_diff_goal.h5 -------------------------------------------------------------------------------- /dual_ur5_control/script/dual_ur5_joint_trajectory_same_start_goal.h5: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/dual_ur5_control/script/dual_ur5_joint_trajectory_same_start_goal.h5 -------------------------------------------------------------------------------- /dual_ur5_control/script/dual_ur5_whole_cart_traj_concat_2_no_delay.h5: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/dual_ur5_control/script/dual_ur5_whole_cart_traj_concat_2_no_delay.h5 -------------------------------------------------------------------------------- /dual_ur5_control/script/dual_ur5_whole_cart_traj_concat_2_with_delay.h5: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/dual_ur5_control/script/dual_ur5_whole_cart_traj_concat_2_with_delay.h5 -------------------------------------------------------------------------------- /dual_ur5_control/script/dual_ur5_whole_traj_concat_2(using plan_go really slow).h5: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/dual_ur5_control/script/dual_ur5_whole_traj_concat_2(using plan_go really slow).h5 -------------------------------------------------------------------------------- /dual_ur5_control/script/example_paths_for_TP_comparison.h5: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/dual_ur5_control/script/example_paths_for_TP_comparison.h5 -------------------------------------------------------------------------------- /dual_ur5_control/script/tmp_new_paths_from_primitives.h5: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/dual_ur5_control/script/tmp_new_paths_from_primitives.h5 -------------------------------------------------------------------------------- /dual_ur5_control/script/traj_pair_lr_9-TOTG.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/dual_ur5_control/script/traj_pair_lr_9-TOTG.png -------------------------------------------------------------------------------- /dual_ur5_control/script/traj_pair_lr_9-ori.png: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/dual_ur5_control/script/traj_pair_lr_9-ori.png -------------------------------------------------------------------------------- /dual_ur5_control/sdf/flash_body/meshes/flash_body.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/dual_ur5_control/sdf/flash_body/meshes/flash_body.STL -------------------------------------------------------------------------------- /dual_ur5_control/sdf/flash_body/model.config: -------------------------------------------------------------------------------- 1 | 2 | 3 | flash_body 4 | 1.0 5 | model.sdf 6 | 7 | 8 | Yuwei Liang 9 | lyw.liangyuwei@gmail.com 10 | 11 | 12 | 13 | 14 | -------------------------------------------------------------------------------- /dual_ur5_control/sdf/flash_body/model.sdf: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 0 0 0 0 0 0 7 | 8 | 9 | 10 | 11 | 12 | model://flash_body/meshes/flash_body.STL 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | model://flash_body/meshes/flash_body.STL 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | -------------------------------------------------------------------------------- /dual_ur5_control/srv/CartToJnt.srv: -------------------------------------------------------------------------------- 1 | string group_name 2 | geometry_msgs/Pose[] waypoints 3 | 4 | --- 5 | 6 | moveit_msgs/RobotTrajectory plan 7 | -------------------------------------------------------------------------------- /dual_ur5_control/srv/JntToCart.srv: -------------------------------------------------------------------------------- 1 | bool left_or_right 2 | trajectory_msgs/JointTrajectoryPoint[] joint_trajectory 3 | 4 | --- 5 | 6 | geometry_msgs/Pose[] cart_trajectory 7 | -------------------------------------------------------------------------------- /dual_ur5_moveit_config/.setup_assistant: -------------------------------------------------------------------------------- 1 | moveit_setup_assistant_config: 2 | URDF: 3 | package: ur_description 4 | relative_path: urdf/ur5_robot.urdf 5 | xacro_args: "--inorder " 6 | SRDF: 7 | relative_path: config/ur5.srdf 8 | CONFIG: 9 | author_name: cxc 10 | author_email: 474068455@qq.com 11 | generated_timestamp: 1557735305 -------------------------------------------------------------------------------- /dual_ur5_moveit_config/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(dual_ur5_moveit_config) 3 | 4 | find_package(catkin REQUIRED) 5 | 6 | catkin_package() 7 | 8 | install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} 9 | PATTERN "setup_assistant.launch" EXCLUDE) 10 | install(DIRECTORY config DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) 11 | -------------------------------------------------------------------------------- /dual_ur5_moveit_config/config/chomp_planning.yaml: -------------------------------------------------------------------------------- 1 | planning_time_limit: 10.0 2 | max_iterations: 200 3 | max_iterations_after_collision_free: 5 4 | smoothness_cost_weight: 0.1 5 | obstacle_cost_weight: 1.0 6 | learning_rate: 0.01 7 | smoothness_cost_velocity: 0.0 8 | smoothness_cost_acceleration: 1.0 9 | smoothness_cost_jerk: 0.0 10 | ridge_factor: 0.01 11 | use_pseudo_inverse: false 12 | pseudo_inverse_ridge_factor: 1e-4 13 | joint_update_limit: 0.1 14 | collision_clearence: 0.2 15 | collision_threshold: 0.07 16 | use_stochastic_descent: true 17 | enable_failure_recovery: true 18 | max_recovery_attempts: 5 -------------------------------------------------------------------------------- /dual_ur5_moveit_config/config/kinematics.yaml: -------------------------------------------------------------------------------- 1 | left_arm: 2 | kinematics_solver: trac_ik_kinematics_plugin/TRAC_IKKinematicsPlugin #kdl_kinematics_plugin/KDLKinematicsPlugin 3 | solve_type: Distance 4 | kinematics_solver_search_resolution: 0.005 5 | kinematics_solver_timeout: 0.005 6 | # kinematics_solver_attempts: 3 7 | right_arm: 8 | kinematics_solver: trac_ik_kinematics_plugin/TRAC_IKKinematicsPlugin #kdl_kinematics_plugin/KDLKinematicsPlugin 9 | solve_type: Distance 10 | kinematics_solver_search_resolution: 0.005 11 | kinematics_solver_timeout: 0.005 12 | # kinematics_solver_attempts: 3 13 | dual_arms: 14 | kinematics_solver: trac_ik_kinematics_plugin/TRAC_IKKinematicsPlugin #kdl_kinematics_plugin/KDLKinematicsPlugin 15 | solve_type: Distance 16 | kinematics_solver_search_resolution: 0.005 17 | kinematics_solver_timeout: 0.005 18 | # kinematics_solver_attempts: 3 19 | -------------------------------------------------------------------------------- /dual_ur5_moveit_config/config/sensors_3d.yaml: -------------------------------------------------------------------------------- 1 | # The name of this file shouldn't be changed, or else the Setup Assistant won't detect it 2 | sensors: 3 | - filtered_cloud_topic: filtered_cloud 4 | max_range: 5.0 5 | max_update_rate: 1.0 6 | padding_offset: 0.1 7 | padding_scale: 1.0 8 | point_cloud_topic: /head_mount_kinect/depth_registered/points 9 | point_subsample: 1 10 | sensor_plugin: occupancy_map_monitor/PointCloudOctomapUpdater -------------------------------------------------------------------------------- /dual_ur5_moveit_config/launch/chomp_planning_pipeline.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | -------------------------------------------------------------------------------- /dual_ur5_moveit_config/launch/default_warehouse_db.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | -------------------------------------------------------------------------------- /dual_ur5_moveit_config/launch/dual_ur5_moveit_controller_manager.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | -------------------------------------------------------------------------------- /dual_ur5_moveit_config/launch/fake_moveit_controller_manager.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | -------------------------------------------------------------------------------- /dual_ur5_moveit_config/launch/joystick_control.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | -------------------------------------------------------------------------------- /dual_ur5_moveit_config/launch/moveit_rviz.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 13 | 14 | 15 | 16 | 17 | -------------------------------------------------------------------------------- /dual_ur5_moveit_config/launch/planning_pipeline.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | -------------------------------------------------------------------------------- /dual_ur5_moveit_config/launch/ros_controllers.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 10 | 11 | 12 | 14 | 15 | 16 | 17 | 18 | -------------------------------------------------------------------------------- /dual_ur5_moveit_config/launch/run_benchmark_ompl.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | -------------------------------------------------------------------------------- /dual_ur5_moveit_config/launch/sensor_manager.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | -------------------------------------------------------------------------------- /dual_ur5_moveit_config/launch/setup_assistant.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 14 | 15 | 16 | -------------------------------------------------------------------------------- /dual_ur5_moveit_config/launch/ur5_moveit_sensor_manager.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | -------------------------------------------------------------------------------- /dual_ur5_moveit_config/launch/warehouse.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | -------------------------------------------------------------------------------- /dual_ur5_moveit_config/launch/warehouse_settings.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | -------------------------------------------------------------------------------- /dynamic_mapping_params/msg/MappingParams.msg: -------------------------------------------------------------------------------- 1 | float64 l_elbow_scale 2 | float64 l_elbow_offs_x 3 | float64 l_elbow_offs_y 4 | float64 l_elbow_offs_z 5 | 6 | float64 r_elbow_scale 7 | float64 r_elbow_offs_x 8 | float64 r_elbow_offs_y 9 | float64 r_elbow_offs_z 10 | 11 | float64 l_wrist_scale 12 | float64 l_wrist_offs_x 13 | float64 l_wrist_offs_y 14 | float64 l_wrist_offs_z 15 | 16 | float64 r_wrist_scale 17 | float64 r_wrist_offs_x 18 | float64 r_wrist_offs_y 19 | float64 r_wrist_offs_z -------------------------------------------------------------------------------- /human_model/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(human_model) 3 | 4 | ## Compile as C++11, supported in ROS Kinetic and newer 5 | add_compile_options(-std=c++11) 6 | 7 | find_package(catkin REQUIRED COMPONENTS 8 | roscpp 9 | rospy 10 | tf 11 | std_msgs 12 | urdf 13 | controller_manager 14 | joint_state_controller 15 | robot_state_publisher 16 | gazebo_ros_control 17 | ) 18 | 19 | -------------------------------------------------------------------------------- /human_model/urdf/human_model.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/human_model/urdf/human_model.pdf -------------------------------------------------------------------------------- /human_model_moveit_config/.setup_assistant: -------------------------------------------------------------------------------- 1 | moveit_setup_assistant_config: 2 | URDF: 3 | package: human_model 4 | relative_path: urdf/human_model.urdf.xacro 5 | xacro_args: "--inorder " 6 | SRDF: 7 | relative_path: config/human_model.srdf 8 | CONFIG: 9 | author_name: Yuwei Liang 10 | author_email: lyw.liangyuwei@gmail.com 11 | generated_timestamp: 1600503391 -------------------------------------------------------------------------------- /human_model_moveit_config/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(human_model_moveit_config) 3 | 4 | find_package(catkin REQUIRED) 5 | 6 | catkin_package() 7 | 8 | install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} 9 | PATTERN "setup_assistant.launch" EXCLUDE) 10 | install(DIRECTORY config DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) 11 | -------------------------------------------------------------------------------- /human_model_moveit_config/config/chomp_planning.yaml: -------------------------------------------------------------------------------- 1 | planning_time_limit: 10.0 2 | max_iterations: 200 3 | max_iterations_after_collision_free: 5 4 | smoothness_cost_weight: 0.1 5 | obstacle_cost_weight: 1.0 6 | learning_rate: 0.01 7 | smoothness_cost_velocity: 0.0 8 | smoothness_cost_acceleration: 1.0 9 | smoothness_cost_jerk: 0.0 10 | ridge_factor: 0.01 11 | use_pseudo_inverse: false 12 | pseudo_inverse_ridge_factor: 1e-4 13 | joint_update_limit: 0.1 14 | collision_clearence: 0.2 15 | collision_threshold: 0.07 16 | use_stochastic_descent: true 17 | enable_failure_recovery: true 18 | max_recovery_attempts: 5 -------------------------------------------------------------------------------- /human_model_moveit_config/config/kinematics.yaml: -------------------------------------------------------------------------------- 1 | left_arm: 2 | kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin 3 | kinematics_solver_search_resolution: 0.005 4 | kinematics_solver_timeout: 0.005 5 | kinematics_solver_attempts: 3 6 | right_arm: 7 | kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin 8 | kinematics_solver_search_resolution: 0.005 9 | kinematics_solver_timeout: 0.005 10 | kinematics_solver_attempts: 3 -------------------------------------------------------------------------------- /human_model_moveit_config/config/sensors_3d.yaml: -------------------------------------------------------------------------------- 1 | # The name of this file shouldn't be changed, or else the Setup Assistant won't detect it 2 | sensors: 3 | - filtered_cloud_topic: filtered_cloud 4 | max_range: 5.0 5 | max_update_rate: 1.0 6 | padding_offset: 0.1 7 | padding_scale: 1.0 8 | point_cloud_topic: /head_mount_kinect/depth_registered/points 9 | point_subsample: 1 10 | sensor_plugin: occupancy_map_monitor/PointCloudOctomapUpdater -------------------------------------------------------------------------------- /human_model_moveit_config/launch/chomp_planning_pipeline.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | -------------------------------------------------------------------------------- /human_model_moveit_config/launch/default_warehouse_db.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | -------------------------------------------------------------------------------- /human_model_moveit_config/launch/fake_moveit_controller_manager.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | -------------------------------------------------------------------------------- /human_model_moveit_config/launch/human_model_moveit_controller_manager.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | -------------------------------------------------------------------------------- /human_model_moveit_config/launch/human_model_moveit_sensor_manager.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | -------------------------------------------------------------------------------- /human_model_moveit_config/launch/joystick_control.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | -------------------------------------------------------------------------------- /human_model_moveit_config/launch/moveit_rviz.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 13 | 14 | 15 | 16 | 17 | -------------------------------------------------------------------------------- /human_model_moveit_config/launch/planning_pipeline.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | -------------------------------------------------------------------------------- /human_model_moveit_config/launch/ros_controllers.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 10 | 11 | 12 | -------------------------------------------------------------------------------- /human_model_moveit_config/launch/run_benchmark_ompl.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | -------------------------------------------------------------------------------- /human_model_moveit_config/launch/sensor_manager.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | -------------------------------------------------------------------------------- /human_model_moveit_config/launch/setup_assistant.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 14 | 15 | 16 | -------------------------------------------------------------------------------- /human_model_moveit_config/launch/warehouse.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | -------------------------------------------------------------------------------- /human_model_moveit_config/launch/warehouse_settings.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | -------------------------------------------------------------------------------- /inspire_hand_description/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | 3 | project(inspire_hand_description) 4 | 5 | find_package(catkin REQUIRED) 6 | 7 | catkin_package() 8 | 9 | find_package(roslaunch) 10 | 11 | foreach(dir config launch meshes urdf) 12 | install(DIRECTORY ${dir}/ 13 | DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/${dir}) 14 | endforeach(dir) 15 | -------------------------------------------------------------------------------- /inspire_hand_description/config/joint_names_left.yaml: -------------------------------------------------------------------------------- 1 | controller_joint_names: ['Link1', 'Link11', 'Link2', 'Link22', 'Link3', 'Link33', 'Link4', 'Link44', 'Link5', 'Link51', 'Link52', 'Link53', ] 2 | -------------------------------------------------------------------------------- /inspire_hand_description/config/joint_names_right.yaml: -------------------------------------------------------------------------------- 1 | controller_joint_names: ['link1', 'link11', 'link2', 'link22', 'link3', 'link33', 'link4', 'link44', 'link5', 'link51', 'link52', 'link53', ] 2 | -------------------------------------------------------------------------------- /inspire_hand_description/launch/display_left.launch: -------------------------------------------------------------------------------- 1 | 2 | 4 | 7 | 10 | 13 | 17 | 21 | 26 | 27 | -------------------------------------------------------------------------------- /inspire_hand_description/launch/display_right.launch: -------------------------------------------------------------------------------- 1 | 2 | 4 | 7 | 10 | 13 | 17 | 21 | 26 | 27 | -------------------------------------------------------------------------------- /inspire_hand_description/launch/gazebo_left.launch: -------------------------------------------------------------------------------- 1 | 2 | 4 | 9 | 15 | 20 | 21 | -------------------------------------------------------------------------------- /inspire_hand_description/launch/gazebo_right.launch: -------------------------------------------------------------------------------- 1 | 2 | 4 | 9 | 15 | 20 | 21 | -------------------------------------------------------------------------------- /inspire_hand_description/meshes/left/link1.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/inspire_hand_description/meshes/left/link1.STL -------------------------------------------------------------------------------- /inspire_hand_description/meshes/left/link11.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/inspire_hand_description/meshes/left/link11.STL -------------------------------------------------------------------------------- /inspire_hand_description/meshes/left/link111.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/inspire_hand_description/meshes/left/link111.STL -------------------------------------------------------------------------------- /inspire_hand_description/meshes/left/link2.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/inspire_hand_description/meshes/left/link2.STL -------------------------------------------------------------------------------- /inspire_hand_description/meshes/left/link22.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/inspire_hand_description/meshes/left/link22.STL -------------------------------------------------------------------------------- /inspire_hand_description/meshes/left/link3.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/inspire_hand_description/meshes/left/link3.STL -------------------------------------------------------------------------------- /inspire_hand_description/meshes/left/link33.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/inspire_hand_description/meshes/left/link33.STL -------------------------------------------------------------------------------- /inspire_hand_description/meshes/left/link4.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/inspire_hand_description/meshes/left/link4.STL -------------------------------------------------------------------------------- /inspire_hand_description/meshes/left/link44.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/inspire_hand_description/meshes/left/link44.STL -------------------------------------------------------------------------------- /inspire_hand_description/meshes/left/link5.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/inspire_hand_description/meshes/left/link5.STL -------------------------------------------------------------------------------- /inspire_hand_description/meshes/left/link51.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/inspire_hand_description/meshes/left/link51.STL -------------------------------------------------------------------------------- /inspire_hand_description/meshes/left/link52.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/inspire_hand_description/meshes/left/link52.STL -------------------------------------------------------------------------------- /inspire_hand_description/meshes/left/link53.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/inspire_hand_description/meshes/left/link53.STL -------------------------------------------------------------------------------- /inspire_hand_description/meshes/right/Link1.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/inspire_hand_description/meshes/right/Link1.STL -------------------------------------------------------------------------------- /inspire_hand_description/meshes/right/Link11.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/inspire_hand_description/meshes/right/Link11.STL -------------------------------------------------------------------------------- /inspire_hand_description/meshes/right/Link111.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/inspire_hand_description/meshes/right/Link111.STL -------------------------------------------------------------------------------- /inspire_hand_description/meshes/right/Link2.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/inspire_hand_description/meshes/right/Link2.STL -------------------------------------------------------------------------------- /inspire_hand_description/meshes/right/Link22.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/inspire_hand_description/meshes/right/Link22.STL -------------------------------------------------------------------------------- /inspire_hand_description/meshes/right/Link3.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/inspire_hand_description/meshes/right/Link3.STL -------------------------------------------------------------------------------- /inspire_hand_description/meshes/right/Link33.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/inspire_hand_description/meshes/right/Link33.STL -------------------------------------------------------------------------------- /inspire_hand_description/meshes/right/Link4.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/inspire_hand_description/meshes/right/Link4.STL -------------------------------------------------------------------------------- /inspire_hand_description/meshes/right/Link44.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/inspire_hand_description/meshes/right/Link44.STL -------------------------------------------------------------------------------- /inspire_hand_description/meshes/right/Link5.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/inspire_hand_description/meshes/right/Link5.STL -------------------------------------------------------------------------------- /inspire_hand_description/meshes/right/Link51.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/inspire_hand_description/meshes/right/Link51.STL -------------------------------------------------------------------------------- /inspire_hand_description/meshes/right/Link52.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/inspire_hand_description/meshes/right/Link52.STL -------------------------------------------------------------------------------- /inspire_hand_description/meshes/right/Link53.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/inspire_hand_description/meshes/right/Link53.STL -------------------------------------------------------------------------------- /inspire_hand_description/package.xml: -------------------------------------------------------------------------------- 1 | 2 | inspire_hand_description 3 | 1.0.0 4 | 5 |

URDF Description package for urdf-five3

6 |

This package contains configuration data, 3D models and launch files 7 | for urdf-five3 robot

8 |
9 | me 10 | 11 | BSD 12 | catkin 13 | roslaunch 14 | robot_state_publisher 15 | rviz 16 | joint_state_publisher 17 | gazebo 18 | 19 | 20 | 21 |
22 | -------------------------------------------------------------------------------- /inspire_hand_driver/launch/hand_control.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | -------------------------------------------------------------------------------- /inspire_hand_driver/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | inspire_hand 4 | 1.0.0 5 | RS232 and RS485 control node for basic communication with inspire hand 6 | 7 | Hanson Du 8 | BSD 9 | http://www.inspire-robots.com/ 10 | Hanson Du 11 | 12 | catkin 13 | roscpp 14 | serial 15 | message_generation 16 | tf 17 | 18 | roscpp 19 | serial 20 | tf 21 | 22 | 23 | -------------------------------------------------------------------------------- /inspire_hand_driver/srv/get_angle_act.srv: -------------------------------------------------------------------------------- 1 | --- 2 | float32[6] curangle 3 | -------------------------------------------------------------------------------- /inspire_hand_driver/srv/get_angle_set.srv: -------------------------------------------------------------------------------- 1 | --- 2 | float32[6] setangle -------------------------------------------------------------------------------- /inspire_hand_driver/srv/get_current.srv: -------------------------------------------------------------------------------- 1 | --- 2 | float32[6] current -------------------------------------------------------------------------------- /inspire_hand_driver/srv/get_error.srv: -------------------------------------------------------------------------------- 1 | --- 2 | float32[6] errorvalue -------------------------------------------------------------------------------- /inspire_hand_driver/srv/get_force_act.srv: -------------------------------------------------------------------------------- 1 | --- 2 | float32[6] curforce -------------------------------------------------------------------------------- /inspire_hand_driver/srv/get_force_set.srv: -------------------------------------------------------------------------------- 1 | --- 2 | float32[6] setforce -------------------------------------------------------------------------------- /inspire_hand_driver/srv/get_pos_act.srv: -------------------------------------------------------------------------------- 1 | --- 2 | float32[6] curpos 3 | -------------------------------------------------------------------------------- /inspire_hand_driver/srv/get_pos_set.srv: -------------------------------------------------------------------------------- 1 | --- 2 | float32[6] setpos -------------------------------------------------------------------------------- /inspire_hand_driver/srv/get_status.srv: -------------------------------------------------------------------------------- 1 | --- 2 | float32[6] statusvalue -------------------------------------------------------------------------------- /inspire_hand_driver/srv/get_temp.srv: -------------------------------------------------------------------------------- 1 | --- 2 | float32[6] tempvalue -------------------------------------------------------------------------------- /inspire_hand_driver/srv/set_angle.srv: -------------------------------------------------------------------------------- 1 | int32 angle0 2 | int32 angle1 3 | int32 angle2 4 | int32 angle3 5 | int32 angle4 6 | int32 angle5 7 | --- 8 | bool angle_accepted -------------------------------------------------------------------------------- /inspire_hand_driver/srv/set_clear_error.srv: -------------------------------------------------------------------------------- 1 | --- 2 | bool setclear_error_accepted -------------------------------------------------------------------------------- /inspire_hand_driver/srv/set_current_limit.srv: -------------------------------------------------------------------------------- 1 | int32 current0 2 | int32 current1 3 | int32 current2 4 | int32 current3 5 | int32 current4 6 | int32 current5 7 | --- 8 | bool current_limit_accepted -------------------------------------------------------------------------------- /inspire_hand_driver/srv/set_default_force.srv: -------------------------------------------------------------------------------- 1 | int32 force0 2 | int32 force1 3 | int32 force2 4 | int32 force3 5 | int32 force4 6 | int32 force5 7 | --- 8 | bool default_force_accepted 9 | -------------------------------------------------------------------------------- /inspire_hand_driver/srv/set_default_speed.srv: -------------------------------------------------------------------------------- 1 | int32 speed0 2 | int32 speed1 3 | int32 speed2 4 | int32 speed3 5 | int32 speed4 6 | int32 speed5 7 | --- 8 | bool default_speed_accepted -------------------------------------------------------------------------------- /inspire_hand_driver/srv/set_force.srv: -------------------------------------------------------------------------------- 1 | int32 force0 2 | int32 force1 3 | int32 force2 4 | int32 force3 5 | int32 force4 6 | int32 force5 7 | --- 8 | bool force_accepted 9 | -------------------------------------------------------------------------------- /inspire_hand_driver/srv/set_force_clb.srv: -------------------------------------------------------------------------------- 1 | --- 2 | bool setforce_clb_accepted 3 | -------------------------------------------------------------------------------- /inspire_hand_driver/srv/set_gesture_no.srv: -------------------------------------------------------------------------------- 1 | int32 gesture_no 2 | --- 3 | bool gesture_nograb 4 | -------------------------------------------------------------------------------- /inspire_hand_driver/srv/set_id.srv: -------------------------------------------------------------------------------- 1 | int32 id 2 | --- 3 | bool idgrab 4 | -------------------------------------------------------------------------------- /inspire_hand_driver/srv/set_pos.srv: -------------------------------------------------------------------------------- 1 | int32 pos0 2 | int32 pos1 3 | int32 pos2 4 | int32 pos3 5 | int32 pos4 6 | int32 pos5 7 | --- 8 | bool pos_accepted -------------------------------------------------------------------------------- /inspire_hand_driver/srv/set_redu_ratio.srv: -------------------------------------------------------------------------------- 1 | int32 redu_ratio 2 | --- 3 | bool redu_ratiograb 4 | -------------------------------------------------------------------------------- /inspire_hand_driver/srv/set_reset_para.srv: -------------------------------------------------------------------------------- 1 | --- 2 | bool setreset_para_accepted -------------------------------------------------------------------------------- /inspire_hand_driver/srv/set_save_flash.srv: -------------------------------------------------------------------------------- 1 | --- 2 | bool setsave_flash_accepted -------------------------------------------------------------------------------- /inspire_hand_driver/srv/set_speed.srv: -------------------------------------------------------------------------------- 1 | int32 speed0 2 | int32 speed1 3 | int32 speed2 4 | int32 speed3 5 | int32 speed4 6 | int32 speed5 7 | --- 8 | bool speed_accepted 9 | -------------------------------------------------------------------------------- /inspire_hand_driver/srv/set_user_def_angle.srv: -------------------------------------------------------------------------------- 1 | int32 angle0 2 | int32 angle1 3 | int32 angle2 4 | int32 angle3 5 | int32 angle4 6 | int32 angle5 7 | int32 k 8 | --- 9 | bool angle_accepted 10 | -------------------------------------------------------------------------------- /inspire_right_hand_moveit_config/.setup_assistant: -------------------------------------------------------------------------------- 1 | moveit_setup_assistant_config: 2 | URDF: 3 | package: inspire_hand_description 4 | relative_path: robots/inspire_hand_right.urdf 5 | xacro_args: "--inorder " 6 | SRDF: 7 | relative_path: config/inspire_hand_right.srdf 8 | CONFIG: 9 | author_name: Yuwei Liang 10 | author_email: lyw.liangyuwei@gmail.com 11 | generated_timestamp: 1578445391 -------------------------------------------------------------------------------- /inspire_right_hand_moveit_config/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(inspire_right_hand_moveit_config) 3 | 4 | find_package(catkin REQUIRED) 5 | 6 | catkin_package() 7 | 8 | install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} 9 | PATTERN "setup_assistant.launch" EXCLUDE) 10 | install(DIRECTORY config DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) 11 | -------------------------------------------------------------------------------- /inspire_right_hand_moveit_config/config/chomp_planning.yaml: -------------------------------------------------------------------------------- 1 | planning_time_limit: 10.0 2 | max_iterations: 200 3 | max_iterations_after_collision_free: 5 4 | smoothness_cost_weight: 0.1 5 | obstacle_cost_weight: 1.0 6 | learning_rate: 0.01 7 | smoothness_cost_velocity: 0.0 8 | smoothness_cost_acceleration: 1.0 9 | smoothness_cost_jerk: 0.0 10 | ridge_factor: 0.01 11 | use_pseudo_inverse: false 12 | pseudo_inverse_ridge_factor: 1e-4 13 | joint_update_limit: 0.1 14 | collision_clearence: 0.2 15 | collision_threshold: 0.07 16 | use_stochastic_descent: true 17 | enable_failure_recovery: true 18 | max_recovery_attempts: 5 -------------------------------------------------------------------------------- /inspire_right_hand_moveit_config/config/fake_controllers.yaml: -------------------------------------------------------------------------------- 1 | controller_list: 2 | - name: fake_right_hand_controller 3 | joints: 4 | - Link1 5 | - Link11 6 | - Link2 7 | - Link22 8 | - Link3 9 | - Link33 10 | - Link4 11 | - Link44 12 | - Link5 13 | - Link51 14 | - Link52 15 | - Link53 -------------------------------------------------------------------------------- /inspire_right_hand_moveit_config/config/kinematics.yaml: -------------------------------------------------------------------------------- 1 | {} -------------------------------------------------------------------------------- /inspire_right_hand_moveit_config/config/ros_controllers.yaml: -------------------------------------------------------------------------------- 1 | # MoveIt-specific simulation settings 2 | moveit_sim_hw_interface: 3 | joint_model_group: controllers_initial_group_ 4 | joint_model_group_pose: controllers_initial_pose_ 5 | # Settings for ros_control control loop 6 | generic_hw_control_loop: 7 | loop_hz: 300 8 | cycle_time_error_threshold: 0.01 9 | # Settings for ros_control hardware interface 10 | hardware_interface: 11 | joints: 12 | - Link1 13 | - Link11 14 | - Link2 15 | - Link22 16 | - Link3 17 | - Link33 18 | - Link4 19 | - Link44 20 | - Link5 21 | - Link51 22 | - Link52 23 | - Link53 24 | sim_control_mode: 1 # 0: position, 1: velocity 25 | # Publish all joint states 26 | # Creates the /joint_states topic necessary in ROS 27 | joint_state_controller: 28 | type: joint_state_controller/JointStateController 29 | publish_rate: 50 30 | controller_list: 31 | [] -------------------------------------------------------------------------------- /inspire_right_hand_moveit_config/config/sensors_3d.yaml: -------------------------------------------------------------------------------- 1 | # The name of this file shouldn't be changed, or else the Setup Assistant won't detect it 2 | sensors: 3 | - {} -------------------------------------------------------------------------------- /inspire_right_hand_moveit_config/launch/chomp_planning_pipeline.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | -------------------------------------------------------------------------------- /inspire_right_hand_moveit_config/launch/default_warehouse_db.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | -------------------------------------------------------------------------------- /inspire_right_hand_moveit_config/launch/fake_moveit_controller_manager.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | -------------------------------------------------------------------------------- /inspire_right_hand_moveit_config/launch/inspire_hand_right_moveit_controller_manager.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | -------------------------------------------------------------------------------- /inspire_right_hand_moveit_config/launch/inspire_hand_right_moveit_sensor_manager.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | -------------------------------------------------------------------------------- /inspire_right_hand_moveit_config/launch/joystick_control.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | -------------------------------------------------------------------------------- /inspire_right_hand_moveit_config/launch/moveit_rviz.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 13 | 14 | 15 | 16 | 17 | -------------------------------------------------------------------------------- /inspire_right_hand_moveit_config/launch/planning_pipeline.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | -------------------------------------------------------------------------------- /inspire_right_hand_moveit_config/launch/ros_controllers.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 10 | 11 | 12 | -------------------------------------------------------------------------------- /inspire_right_hand_moveit_config/launch/run_benchmark_ompl.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | -------------------------------------------------------------------------------- /inspire_right_hand_moveit_config/launch/sensor_manager.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | -------------------------------------------------------------------------------- /inspire_right_hand_moveit_config/launch/setup_assistant.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 14 | 15 | 16 | -------------------------------------------------------------------------------- /inspire_right_hand_moveit_config/launch/warehouse.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | -------------------------------------------------------------------------------- /inspire_right_hand_moveit_config/launch/warehouse_settings.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | -------------------------------------------------------------------------------- /raw_totg/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | raw_totg 4 | 0.0.0 5 | The raw_totg package 6 | 7 | 8 | liangyuwei 9 | 10 | BSD 11 | 12 | message_generation 13 | 14 | message_runtime 15 | 16 | catkin 17 | 18 | 19 | 20 | -------------------------------------------------------------------------------- /raw_totg/src/plotTrajectory.m: -------------------------------------------------------------------------------- 1 | trajectory = importdata('trajectory.txt'); 2 | maxVelocity = importdata('maxVelocity.txt'); 3 | plot(maxVelocity(:,1), maxVelocity(:,2), maxVelocity(:,1), maxVelocity(:,3), trajectory(:,1), trajectory(:,2), '.') 4 | -------------------------------------------------------------------------------- /raw_totg/srv/GetMinTime.srv: -------------------------------------------------------------------------------- 1 | trajectory_msgs/JointTrajectoryPoint[] path 2 | float64[] vel_limits 3 | float64[] acc_limits 4 | 5 | --- 6 | 7 | float64 min_time 8 | -------------------------------------------------------------------------------- /raw_totg/srv/PathToTraj.srv: -------------------------------------------------------------------------------- 1 | trajectory_msgs/JointTrajectoryPoint[] path 2 | float64[] vel_limits 3 | float64[] acc_limits 4 | float64 timestep 5 | 6 | --- 7 | 8 | trajectory_msgs/JointTrajectoryPoint[] traj 9 | -------------------------------------------------------------------------------- /realtime_motion_retargeting/msg/ControlMsg.msg: -------------------------------------------------------------------------------- 1 | float64[] l_arm_joint_angle 2 | float64[] r_arm_joint_angle 3 | float64[] l_hand_joint_angle 4 | float64[] r_hand_joint_angle -------------------------------------------------------------------------------- /realtime_motion_retargeting/msg/MotionMsg.msg: -------------------------------------------------------------------------------- 1 | float64[] l_wrist_pos 2 | float64[] r_wrist_pos 3 | float64[] l_wrist_quat 4 | float64[] r_wrist_quat 5 | float64[] l_elbow_pos 6 | float64[] r_elbow_pos 7 | float64[] l_glove_angle 8 | float64[] r_glove_angle -------------------------------------------------------------------------------- /sign_language_robot_control/launch/display_sign_language_robot.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | -------------------------------------------------------------------------------- /sign_language_robot_control/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | sign_language_robot_control 4 | 0.0.0 5 | The sign_language_robot_control package 6 | 7 | liangyuwei 8 | 9 | TODO 10 | 11 | 12 | roscpp 13 | shape_msgs 14 | moveit_msgs 15 | geometry_msgs 16 | kdl_parser 17 | 18 | kdl_parser 19 | 20 | 21 | catkin 22 | 23 | 24 | 25 | 26 | -------------------------------------------------------------------------------- /sign_language_robot_control/script/fake_elbow_wrist_path_1.h5: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/sign_language_robot_control/script/fake_elbow_wrist_path_1.h5 -------------------------------------------------------------------------------- /sign_language_robot_control/script/fake_elbow_wrist_paths.h5: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/sign_language_robot_control/script/fake_elbow_wrist_paths.h5 -------------------------------------------------------------------------------- /sign_language_robot_control/script/ik_results.h5: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/sign_language_robot_control/script/ik_results.h5 -------------------------------------------------------------------------------- /sign_language_robot_control/script/sign-motion-viapoints.xlsx: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/sign_language_robot_control/script/sign-motion-viapoints.xlsx -------------------------------------------------------------------------------- /sign_language_robot_control/src/mocap_combined_wrist_pos_ori_elbow_pos_paths.h5: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/sign_language_robot_control/src/mocap_combined_wrist_pos_ori_elbow_pos_paths.h5 -------------------------------------------------------------------------------- /sign_language_robot_control/src/mocap_paths.h5: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/sign_language_robot_control/src/mocap_paths.h5 -------------------------------------------------------------------------------- /sign_language_robot_moveit_config/.setup_assistant: -------------------------------------------------------------------------------- 1 | moveit_setup_assistant_config: 2 | URDF: 3 | package: ur_description 4 | relative_path: urdf/ur5_robot_with_hands.urdf 5 | xacro_args: "--inorder " 6 | SRDF: 7 | relative_path: config/ur5.srdf 8 | CONFIG: 9 | author_name: Yuwei Liang 10 | author_email: lyw.liangyuwei@gmail.com 11 | generated_timestamp: 1578899299 -------------------------------------------------------------------------------- /sign_language_robot_moveit_config/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(sign_language_robot_moveit_config) 3 | 4 | find_package(catkin REQUIRED) 5 | 6 | catkin_package() 7 | 8 | install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} 9 | PATTERN "setup_assistant.launch" EXCLUDE) 10 | install(DIRECTORY config DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) 11 | -------------------------------------------------------------------------------- /sign_language_robot_moveit_config/config/chomp_planning.yaml: -------------------------------------------------------------------------------- 1 | planning_time_limit: 10.0 2 | max_iterations: 200 3 | max_iterations_after_collision_free: 5 4 | smoothness_cost_weight: 0.1 5 | obstacle_cost_weight: 1.0 6 | learning_rate: 0.01 7 | smoothness_cost_velocity: 0.0 8 | smoothness_cost_acceleration: 1.0 9 | smoothness_cost_jerk: 0.0 10 | ridge_factor: 0.01 11 | use_pseudo_inverse: false 12 | pseudo_inverse_ridge_factor: 1e-4 13 | joint_update_limit: 0.1 14 | collision_clearence: 0.2 15 | collision_threshold: 0.07 16 | use_stochastic_descent: true 17 | enable_failure_recovery: true 18 | max_recovery_attempts: 5 -------------------------------------------------------------------------------- /sign_language_robot_moveit_config/config/sensors_3d.yaml: -------------------------------------------------------------------------------- 1 | # The name of this file shouldn't be changed, or else the Setup Assistant won't detect it 2 | sensors: 3 | - filtered_cloud_topic: filtered_cloud 4 | max_range: 5.0 5 | max_update_rate: 1.0 6 | padding_offset: 0.1 7 | padding_scale: 1.0 8 | point_cloud_topic: /head_mount_kinect/depth_registered/points 9 | point_subsample: 1 10 | sensor_plugin: occupancy_map_monitor/PointCloudOctomapUpdater -------------------------------------------------------------------------------- /sign_language_robot_moveit_config/launch/chomp_planning_pipeline.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | -------------------------------------------------------------------------------- /sign_language_robot_moveit_config/launch/default_warehouse_db.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | -------------------------------------------------------------------------------- /sign_language_robot_moveit_config/launch/fake_moveit_controller_manager.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | -------------------------------------------------------------------------------- /sign_language_robot_moveit_config/launch/fake_moveit_controller_manager.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | -------------------------------------------------------------------------------- /sign_language_robot_moveit_config/launch/joystick_control.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | -------------------------------------------------------------------------------- /sign_language_robot_moveit_config/launch/moveit_rviz.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 13 | 14 | 15 | 16 | 17 | -------------------------------------------------------------------------------- /sign_language_robot_moveit_config/launch/planning_pipeline.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | -------------------------------------------------------------------------------- /sign_language_robot_moveit_config/launch/ros_controllers.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 10 | 11 | 12 | -------------------------------------------------------------------------------- /sign_language_robot_moveit_config/launch/run_benchmark_ompl.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | -------------------------------------------------------------------------------- /sign_language_robot_moveit_config/launch/sensor_manager.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | -------------------------------------------------------------------------------- /sign_language_robot_moveit_config/launch/setup_assistant.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 14 | 15 | 16 | -------------------------------------------------------------------------------- /sign_language_robot_moveit_config/launch/sign_language_robot_moveit_controller_manager.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | -------------------------------------------------------------------------------- /sign_language_robot_moveit_config/launch/ur5_moveit_controller_manager.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | -------------------------------------------------------------------------------- /sign_language_robot_moveit_config/launch/ur5_moveit_sensor_manager.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | -------------------------------------------------------------------------------- /sign_language_robot_moveit_config/launch/warehouse.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | -------------------------------------------------------------------------------- /sign_language_robot_moveit_config/launch/warehouse_settings.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | -------------------------------------------------------------------------------- /universal_robot/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(universal_robot) 3 | find_package(catkin REQUIRED) 4 | catkin_metapackage() 5 | -------------------------------------------------------------------------------- /ur5_moveit_config/.setup_assistant: -------------------------------------------------------------------------------- 1 | moveit_setup_assistant_config: 2 | URDF: 3 | package: ur_description 4 | relative_path: urdf/ur5_robot.urdf.xacro 5 | SRDF: 6 | relative_path: config/ur5.srdf 7 | CONFIG: 8 | generated_timestamp: 1413877529 -------------------------------------------------------------------------------- /ur5_moveit_config/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(ur5_moveit_config) 3 | 4 | find_package(catkin REQUIRED) 5 | 6 | catkin_package() 7 | 8 | if (CATKIN_ENABLE_TESTING) 9 | find_package(roslaunch REQUIRED) 10 | roslaunch_add_file_check(tests/moveit_planning_execution.xml) 11 | endif() 12 | 13 | install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) 14 | install(DIRECTORY config DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) 15 | -------------------------------------------------------------------------------- /ur5_moveit_config/config/controllers.yaml: -------------------------------------------------------------------------------- 1 | controller_list: 2 | 3 | - name: "left" 4 | action_ns: left_follow_joint_trajectory 5 | type: FollowJointTrajectory 6 | joints: 7 | - left_shoulder_pan_joint 8 | - left_shoulder_lift_joint 9 | - left_elbow_joint 10 | - left_wrist_1_joint 11 | - left_wrist_2_joint 12 | - left_wrist_3_joint 13 | 14 | - name: "right" 15 | action_ns: right_follow_joint_trajectory 16 | type: FollowJointTrajectory 17 | joints: 18 | - right_shoulder_pan_joint 19 | - right_shoulder_lift_joint 20 | - right_elbow_joint 21 | - right_wrist_1_joint 22 | - right_wrist_2_joint 23 | - right_wrist_3_joint 24 | -------------------------------------------------------------------------------- /ur5_moveit_config/config/fake_controllers.yaml: -------------------------------------------------------------------------------- 1 | controller_list: 2 | - name: fake_manipulator_controller 3 | joints: 4 | - shoulder_pan_joint 5 | - shoulder_lift_joint 6 | - elbow_joint 7 | - wrist_1_joint 8 | - wrist_2_joint 9 | - wrist_3_joint 10 | - name: fake_endeffector_controller 11 | joints: 12 | [] -------------------------------------------------------------------------------- /ur5_moveit_config/config/kinematics.yaml: -------------------------------------------------------------------------------- 1 | #manipulator: 2 | # kinematics_solver: ur_kinematics/UR5KinematicsPlugin 3 | # kinematics_solver_search_resolution: 0.005 4 | # kinematics_solver_timeout: 0.005 5 | # kinematics_solver_attempts: 3 6 | manipulator: 7 | kinematics_solver: ur5_manipulator_kinematics/IKFastKinematicsPlugin 8 | kinematics_solver_search_resolution: 0.005 9 | kinematics_solver_timeout: 0.005 10 | kinematics_solver_attempts: 3 11 | -------------------------------------------------------------------------------- /ur5_moveit_config/launch/default_warehouse_db.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | -------------------------------------------------------------------------------- /ur5_moveit_config/launch/fake_moveit_controller_manager.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | -------------------------------------------------------------------------------- /ur5_moveit_config/launch/moveit_rviz.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 13 | 14 | 15 | 16 | 17 | -------------------------------------------------------------------------------- /ur5_moveit_config/launch/ompl_planning_pipeline.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 8 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | -------------------------------------------------------------------------------- /ur5_moveit_config/launch/planning_pipeline.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | -------------------------------------------------------------------------------- /ur5_moveit_config/launch/run_benchmark_ompl.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | -------------------------------------------------------------------------------- /ur5_moveit_config/launch/sensor_manager.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | -------------------------------------------------------------------------------- /ur5_moveit_config/launch/setup_assistant.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 14 | 15 | 16 | -------------------------------------------------------------------------------- /ur5_moveit_config/launch/ur5_moveit_controller_manager.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | -------------------------------------------------------------------------------- /ur5_moveit_config/launch/ur5_moveit_planning_execution.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | -------------------------------------------------------------------------------- /ur5_moveit_config/launch/ur5_moveit_sensor_manager.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | -------------------------------------------------------------------------------- /ur5_moveit_config/launch/warehouse.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | -------------------------------------------------------------------------------- /ur5_moveit_config/launch/warehouse_settings.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | -------------------------------------------------------------------------------- /ur5_moveit_config/tests/moveit_planning_execution.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | -------------------------------------------------------------------------------- /ur_description/launch/dual_ur5_upload.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | -------------------------------------------------------------------------------- /ur_description/launch/load_flash.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | -------------------------------------------------------------------------------- /ur_description/launch/sign_language_robot_upload.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | -------------------------------------------------------------------------------- /ur_description/launch/test.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | -------------------------------------------------------------------------------- /ur_description/launch/ur10_upload.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | -------------------------------------------------------------------------------- /ur_description/launch/ur3_upload.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | -------------------------------------------------------------------------------- /ur_description/launch/ur5_upload.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | -------------------------------------------------------------------------------- /ur_description/meshes/flash_body/meshes/flash_body.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/ur_description/meshes/flash_body/meshes/flash_body.STL -------------------------------------------------------------------------------- /ur_description/meshes/flash_body/meshes/flash_body_final.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/ur_description/meshes/flash_body/meshes/flash_body_final.STL -------------------------------------------------------------------------------- /ur_description/meshes/flash_body/meshes/flash_body_realign_frame1.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/ur_description/meshes/flash_body/meshes/flash_body_realign_frame1.STL -------------------------------------------------------------------------------- /ur_description/meshes/flash_body/meshes/flash_body_realign_frame1_new.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/ur_description/meshes/flash_body/meshes/flash_body_realign_frame1_new.STL -------------------------------------------------------------------------------- /ur_description/meshes/flash_body/meshes/flash_body_realign_frame2.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/ur_description/meshes/flash_body/meshes/flash_body_realign_frame2.STL -------------------------------------------------------------------------------- /ur_description/meshes/flash_body/meshes/flash_body_realign_frame3.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/ur_description/meshes/flash_body/meshes/flash_body_realign_frame3.STL -------------------------------------------------------------------------------- /ur_description/meshes/flash_body/model.config: -------------------------------------------------------------------------------- 1 | 2 | 3 | flash_body 4 | 1.0 5 | model.sdf 6 | 7 | 8 | Yuwei Liang 9 | lyw.liangyuwei@gmail.com 10 | 11 | 12 | 13 | A flash body model 14 | 15 | 16 | 17 | -------------------------------------------------------------------------------- /ur_description/meshes/flash_hat/meshes/flash_hat_final.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/ur_description/meshes/flash_hat/meshes/flash_hat_final.STL -------------------------------------------------------------------------------- /ur_description/meshes/flash_hat/model.config: -------------------------------------------------------------------------------- 1 | 2 | 3 | flash_hat 4 | 1.0 5 | model_test.sdf 6 | 7 | 8 | Yuwei Liang 9 | lyw.liangyuwei@gmail.com 10 | 11 | 12 | 13 | A flash hat model 14 | 15 | 16 | 17 | -------------------------------------------------------------------------------- /ur_description/meshes/gripper/base.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/ur_description/meshes/gripper/base.stl -------------------------------------------------------------------------------- /ur_description/meshes/gripper/l1.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/ur_description/meshes/gripper/l1.stl -------------------------------------------------------------------------------- /ur_description/meshes/gripper/l2.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/ur_description/meshes/gripper/l2.stl -------------------------------------------------------------------------------- /ur_description/meshes/gripper/r1.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/ur_description/meshes/gripper/r1.stl -------------------------------------------------------------------------------- /ur_description/meshes/gripper/r2.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/ur_description/meshes/gripper/r2.stl -------------------------------------------------------------------------------- /ur_description/meshes/ur10/collision/base.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/ur_description/meshes/ur10/collision/base.stl -------------------------------------------------------------------------------- /ur_description/meshes/ur10/collision/forearm.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/ur_description/meshes/ur10/collision/forearm.stl -------------------------------------------------------------------------------- /ur_description/meshes/ur10/collision/shoulder.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/ur_description/meshes/ur10/collision/shoulder.stl -------------------------------------------------------------------------------- /ur_description/meshes/ur10/collision/upperarm.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/ur_description/meshes/ur10/collision/upperarm.stl -------------------------------------------------------------------------------- /ur_description/meshes/ur10/collision/wrist1.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/ur_description/meshes/ur10/collision/wrist1.stl -------------------------------------------------------------------------------- /ur_description/meshes/ur10/collision/wrist2.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/ur_description/meshes/ur10/collision/wrist2.stl -------------------------------------------------------------------------------- /ur_description/meshes/ur10/collision/wrist3.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/ur_description/meshes/ur10/collision/wrist3.stl -------------------------------------------------------------------------------- /ur_description/meshes/ur3/collision/base.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/ur_description/meshes/ur3/collision/base.stl -------------------------------------------------------------------------------- /ur_description/meshes/ur3/collision/forearm.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/ur_description/meshes/ur3/collision/forearm.stl -------------------------------------------------------------------------------- /ur_description/meshes/ur3/collision/shoulder.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/ur_description/meshes/ur3/collision/shoulder.stl -------------------------------------------------------------------------------- /ur_description/meshes/ur3/collision/upperarm.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/ur_description/meshes/ur3/collision/upperarm.stl -------------------------------------------------------------------------------- /ur_description/meshes/ur3/collision/wrist1.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/ur_description/meshes/ur3/collision/wrist1.stl -------------------------------------------------------------------------------- /ur_description/meshes/ur3/collision/wrist2.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/ur_description/meshes/ur3/collision/wrist2.stl -------------------------------------------------------------------------------- /ur_description/meshes/ur3/collision/wrist3.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/ur_description/meshes/ur3/collision/wrist3.stl -------------------------------------------------------------------------------- /ur_description/meshes/ur5/base_link.STL: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/ur_description/meshes/ur5/base_link.STL -------------------------------------------------------------------------------- /ur_description/meshes/ur5/collision/base.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/ur_description/meshes/ur5/collision/base.stl -------------------------------------------------------------------------------- /ur_description/meshes/ur5/collision/forearm.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/ur_description/meshes/ur5/collision/forearm.stl -------------------------------------------------------------------------------- /ur_description/meshes/ur5/collision/shoulder.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/ur_description/meshes/ur5/collision/shoulder.stl -------------------------------------------------------------------------------- /ur_description/meshes/ur5/collision/upperarm.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/ur_description/meshes/ur5/collision/upperarm.stl -------------------------------------------------------------------------------- /ur_description/meshes/ur5/collision/wrist1.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/ur_description/meshes/ur5/collision/wrist1.stl -------------------------------------------------------------------------------- /ur_description/meshes/ur5/collision/wrist2.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/ur_description/meshes/ur5/collision/wrist2.stl -------------------------------------------------------------------------------- /ur_description/meshes/ur5/collision/wrist3.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/ur_description/meshes/ur5/collision/wrist3.stl -------------------------------------------------------------------------------- /ur_description/model.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/ur_description/model.pdf -------------------------------------------------------------------------------- /ur_description/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | ur_description 4 | 1.2.1 5 | 6 | URDF description for Universal UR5/10 robot arms 7 | 8 | 9 | Wim Meeussen 10 | Kelsey Hawkins 11 | Mathias Ludtke 12 | Felix Messmer 13 | Nadia Hammoudeh Garcia 14 | G.A. vd. Hoorn 15 | 16 | BSD 17 | 18 | http://ros.org/wiki/ur_description 19 | 20 | catkin 21 | urdf 22 | xacro 23 | 24 | 25 | 26 | 27 | -------------------------------------------------------------------------------- /ur_description/urdf/common.gazebo.xacro: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 24 | 25 | 26 | 27 | -------------------------------------------------------------------------------- /ur_description/urdf/ur.gazebo.xacro: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | true 8 | 9 | 10 | true 11 | 12 | 13 | true 14 | 15 | 16 | true 17 | 18 | 19 | true 20 | 21 | 22 | true 23 | 24 | 25 | true 26 | 27 | 28 | 29 | 30 | 31 | -------------------------------------------------------------------------------- /ur_description/urdf/ur10_robot.urdf.xacro: -------------------------------------------------------------------------------- 1 | 2 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | -------------------------------------------------------------------------------- /ur_description/urdf/ur3_robot.urdf.xacro: -------------------------------------------------------------------------------- 1 | 2 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | -------------------------------------------------------------------------------- /ur_description/urdf/ur5.pdf: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/ur_description/urdf/ur5.pdf -------------------------------------------------------------------------------- /ur_description/urdf/ur5_robot.urdf.xacro: -------------------------------------------------------------------------------- 1 | 2 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | -------------------------------------------------------------------------------- /ur_gazebo/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | 3 | project(ur_gazebo) 4 | 5 | find_package(catkin REQUIRED) 6 | 7 | catkin_package() 8 | 9 | if (CATKIN_ENABLE_TESTING) 10 | find_package(roslaunch REQUIRED) 11 | roslaunch_add_file_check(tests/roslaunch_test.xml) 12 | endif() 13 | 14 | install(DIRECTORY launch controller DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) 15 | -------------------------------------------------------------------------------- /ur_gazebo/controller/arm_controller_ur10.yaml: -------------------------------------------------------------------------------- 1 | arm_controller: 2 | type: position_controllers/JointTrajectoryController 3 | joints: 4 | - shoulder_pan_joint 5 | - shoulder_lift_joint 6 | - elbow_joint 7 | - wrist_1_joint 8 | - wrist_2_joint 9 | - wrist_3_joint 10 | constraints: 11 | goal_time: 0.6 12 | stopped_velocity_tolerance: 0.05 13 | shoulder_pan_joint: {trajectory: 0.1, goal: 0.1} 14 | shoulder_lift_joint: {trajectory: 0.1, goal: 0.1} 15 | elbow_joint: {trajectory: 0.1, goal: 0.1} 16 | wrist_1_joint: {trajectory: 0.1, goal: 0.1} 17 | wrist_2_joint: {trajectory: 0.1, goal: 0.1} 18 | wrist_3_joint: {trajectory: 0.1, goal: 0.1} 19 | stop_trajectory_duration: 0.5 20 | state_publish_rate: 25 21 | action_monitor_rate: 10 22 | -------------------------------------------------------------------------------- /ur_gazebo/controller/arm_controller_ur3.yaml: -------------------------------------------------------------------------------- 1 | arm_controller: 2 | type: position_controllers/JointTrajectoryController 3 | joints: 4 | - shoulder_pan_joint 5 | - shoulder_lift_joint 6 | - elbow_joint 7 | - wrist_1_joint 8 | - wrist_2_joint 9 | - wrist_3_joint 10 | constraints: 11 | goal_time: 0.6 12 | stopped_velocity_tolerance: 0.05 13 | shoulder_pan_joint: {trajectory: 0.1, goal: 0.1} 14 | shoulder_lift_joint: {trajectory: 0.1, goal: 0.1} 15 | elbow_joint: {trajectory: 0.1, goal: 0.1} 16 | wrist_1_joint: {trajectory: 0.1, goal: 0.1} 17 | wrist_2_joint: {trajectory: 0.1, goal: 0.1} 18 | wrist_3_joint: {trajectory: 0.1, goal: 0.1} 19 | stop_trajectory_duration: 0.5 20 | state_publish_rate: 25 21 | action_monitor_rate: 10 22 | -------------------------------------------------------------------------------- /ur_gazebo/controller/arm_controller_ur5.yaml: -------------------------------------------------------------------------------- 1 | arm_controller: 2 | type: position_controllers/JointTrajectoryController 3 | joints: 4 | - shoulder_pan_joint 5 | - shoulder_lift_joint 6 | - elbow_joint 7 | - wrist_1_joint 8 | - wrist_2_joint 9 | - wrist_3_joint 10 | constraints: 11 | goal_time: 0.6 12 | stopped_velocity_tolerance: 0.05 13 | shoulder_pan_joint: {trajectory: 0.1, goal: 0.1} 14 | shoulder_lift_joint: {trajectory: 0.1, goal: 0.1} 15 | elbow_joint: {trajectory: 0.1, goal: 0.1} 16 | wrist_1_joint: {trajectory: 0.1, goal: 0.1} 17 | wrist_2_joint: {trajectory: 0.1, goal: 0.1} 18 | wrist_3_joint: {trajectory: 0.1, goal: 0.1} 19 | stop_trajectory_duration: 0.5 20 | state_publish_rate: 25 21 | action_monitor_rate: 10 22 | -------------------------------------------------------------------------------- /ur_gazebo/controller/joint_state_controller.yaml: -------------------------------------------------------------------------------- 1 | joint_state_controller: 2 | type: joint_state_controller/JointStateController 3 | publish_rate: 50 4 | -------------------------------------------------------------------------------- /ur_gazebo/launch/controller_utils.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | -------------------------------------------------------------------------------- /ur_gazebo/launch/ur10_joint_limited.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | -------------------------------------------------------------------------------- /ur_gazebo/launch/ur3_joint_limited.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | -------------------------------------------------------------------------------- /ur_gazebo/launch/ur5_joint_limited.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | -------------------------------------------------------------------------------- /ur_gazebo/tests/roslaunch_test.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | -------------------------------------------------------------------------------- /ur_msgs/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package ur_msgs 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 1.2.1 (2018-01-06) 6 | ------------------ 7 | 8 | 1.2.0 (2017-08-04) 9 | ------------------ 10 | 11 | 1.1.9 (2017-01-02) 12 | ------------------ 13 | * No changes. 14 | 15 | 1.1.8 (2016-12-30) 16 | ------------------ 17 | * all: update maintainers. 18 | * Contributors: gavanderhoorn 19 | 20 | 1.1.7 (2016-12-29) 21 | ------------------ 22 | * Add message definition for ToolData. 23 | * Contributors: Nikolas Engelhard 24 | 25 | 1.1.6 (2016-04-01) 26 | ------------------ 27 | * Moved SetIO FUN constants from driver.py to relevant srv file for easier interaction from other files 28 | * catkin_lint 29 | * Contributors: Thomas Timm Andersen, ipa-fxm 30 | -------------------------------------------------------------------------------- /ur_msgs/msg/Analog.msg: -------------------------------------------------------------------------------- 1 | uint8 pin 2 | float32 state 3 | -------------------------------------------------------------------------------- /ur_msgs/msg/Digital.msg: -------------------------------------------------------------------------------- 1 | uint8 pin 2 | bool state 3 | -------------------------------------------------------------------------------- /ur_msgs/msg/IOStates.msg: -------------------------------------------------------------------------------- 1 | Digital[] digital_in_states 2 | Digital[] digital_out_states 3 | Digital[] flag_states 4 | Analog[] analog_in_states 5 | Analog[] analog_out_states 6 | -------------------------------------------------------------------------------- /ur_msgs/msg/MasterboardDataMsg.msg: -------------------------------------------------------------------------------- 1 | # This data structure contains the MasterboardData structure 2 | # used by the Universal Robots controller 3 | # 4 | # MasterboardData is part of the data structure being send on the 5 | # secondary client communications interface 6 | # 7 | # This data structure is send at 10 Hz on TCP port 30002 8 | # 9 | # Dokumentation can be found on the Universal Robots Support Wiki 10 | # (http://wiki03.lynero.net/Technical/DataStreamFromURController?rev=8) 11 | 12 | int16 digital_input_bits 13 | int16 digital_output_bits 14 | int8 analog_input_range0 15 | int8 analog_input_range1 16 | float64 analog_input0 17 | float64 analog_input1 18 | int8 analog_output_domain0 19 | int8 analog_output_domain1 20 | float64 analog_output0 21 | float64 analog_output1 22 | float32 masterboard_temperature 23 | float32 robot_voltage_48V 24 | float32 robot_current 25 | float32 master_io_current 26 | uint8 master_safety_state 27 | uint8 master_onoff_state 28 | -------------------------------------------------------------------------------- /ur_msgs/msg/RobotStateRTMsg.msg: -------------------------------------------------------------------------------- 1 | # Data structure for the realtime communications interface (aka Matlab interface) 2 | # used by the Universal Robots controller 3 | # 4 | # This data structure is send at 125 Hz on TCP port 30003 5 | # 6 | # Dokumentation can be found on the Universal Robots Support Wiki 7 | # (http://wiki03.lynero.net/Technical/RealTimeClientInterface?rev=9) 8 | 9 | float64 time 10 | float64[] q_target 11 | float64[] qd_target 12 | float64[] qdd_target 13 | float64[] i_target 14 | float64[] m_target 15 | float64[] q_actual 16 | float64[] qd_actual 17 | float64[] i_actual 18 | float64[] tool_acc_values 19 | float64[] tcp_force 20 | float64[] tool_vector 21 | float64[] tcp_speed 22 | float64 digital_input_bits 23 | float64[] motor_temperatures 24 | float64 controller_timer 25 | float64 test_value 26 | float64 robot_mode 27 | float64[] joint_modes 28 | -------------------------------------------------------------------------------- /ur_msgs/msg/ToolDataMsg.msg: -------------------------------------------------------------------------------- 1 | # This data structure contains the ToolData structure 2 | # used by the Universal Robots controller 3 | 4 | int8 ANALOG_INPUT_RANGE_CURRENT = 0 5 | int8 ANALOG_INPUT_RANGE_VOLTAGE = 1 6 | 7 | int8 analog_input_range2 # one of ANALOG_INPUT_RANGE_* 8 | int8 analog_input_range3 # one of ANALOG_INPUT_RANGE_* 9 | float64 analog_input2 10 | float64 analog_input3 11 | float32 tool_voltage_48v 12 | uint8 tool_output_voltage 13 | float32 tool_current 14 | float32 tool_temperature 15 | 16 | uint8 TOOL_BOOTLOADER_MODE = 249 17 | uint8 TOOL_RUNNING_MODE = 253 18 | uint8 TOOL_IDLE_MODE = 255 19 | 20 | uint8 tool_mode # one of TOOL_* 21 | -------------------------------------------------------------------------------- /ur_msgs/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | ur_msgs 4 | 1.2.1 5 | The ur_msgs package 6 | 7 | Andrew Glusiec 8 | Felix Messmer 9 | Nadia Hammoudeh Garcia 10 | G.A. vd. Hoorn 11 | 12 | BSD 13 | 14 | catkin 15 | message_generation 16 | std_msgs 17 | message_runtime 18 | std_msgs 19 | 20 | 21 | 22 | 23 | -------------------------------------------------------------------------------- /ur_msgs/srv/SetIO.srv: -------------------------------------------------------------------------------- 1 | int8 FUN_SET_DIGITAL_OUT = 1 2 | int8 FUN_SET_FLAG = 2 3 | int8 FUN_SET_ANALOG_OUT = 3 4 | int8 FUN_SET_TOOL_VOLTAGE = 4 5 | int8 fun 6 | int8 pin 7 | float32 state 8 | --- 9 | bool success 10 | -------------------------------------------------------------------------------- /ur_msgs/srv/SetPayload.srv: -------------------------------------------------------------------------------- 1 | float32 payload 2 | ----------------------- 3 | bool success 4 | -------------------------------------------------------------------------------- /yumi/.gitignore: -------------------------------------------------------------------------------- 1 | # Lines that start with '#' are comments. 2 | 3 | # Backup and data files 4 | eg/eg.* 5 | *~ 6 | *.bak 7 | *.off 8 | *.x 9 | x.* 10 | r 11 | x 12 | x? 13 | r? 14 | 15 | #Misc 16 | 17 | lbr_fri/fri 18 | 19 | # patch results 20 | *.rej 21 | 22 | # Build products 23 | tmp/* 24 | build/Makefile* 25 | build/CMakeFiles 26 | build/CMakeCache.txt 27 | build/*/Makefile* 28 | build/*/object_script* 29 | build/*/Release/* 30 | build/*/Debug/* 31 | build/*/MinSizeRel/* 32 | build/*/RelWithDebInfo/* 33 | build 34 | 35 | *# 36 | *.# 37 | *.obj 38 | *.dae 39 | *.a 40 | *.dll 41 | *.lib 42 | *.exe 43 | *.bag 44 | *.o 45 | *.md5sum 46 | 47 | # Qt files 48 | *.pro.user 49 | 50 | # DevStudio files 51 | *.bsc 52 | *.ncb 53 | *.pdb 54 | *.suo 55 | *.user 56 | *.ilk 57 | 58 | # CVS files 59 | CVS/* 60 | */CVS/* 61 | */*/CVS/* 62 | */*/*/CVS/* 63 | *.cvsignore 64 | 65 | # Other files 66 | working/ 67 | 68 | yumi_hw/docs/ 69 | 70 | Status API Training Shop Blog About 71 | © 2014 GitHub, Inc. Terms Privacy Security Contact 72 | 73 | -------------------------------------------------------------------------------- /yumi/README.md: -------------------------------------------------------------------------------- 1 | Urdf & Gazebo files for the ABB YuMi (IRB 14000) robot 2 | 3 | ### Dependencies 4 | This package depends on ros-industrial which is not released on kinetic yet. So skip step 2 if you have already install ros-industrial. 5 | 6 | #### Step 1 7 | Install all of these: 8 | ``` 9 | sudo apt-get install ros-kinetic-control-toolbox ros-kinetic-controller-interface ros-kinetic-controller-manager ros-kinetic-joint-limits-interface ros-kinetic-transmission-interface ros-kinetic-moveit-core ros-kinetic-moveit-planners ros-kinetic-moveit-ros-planning 10 | ``` 11 | 12 | #### Step 2 13 | Build the industrial_core package from source. To do that, clone OrebroUniversity's fork of the package from: https://github.com/OrebroUniversity/industrial_core.git into your ros workspace and run `catkin_make`. 14 | 15 | #### Step 3 16 | If your industrial_core is in a different workspace, source the workspace containing industrial_core. 17 | Finally, `catkin_make` the workspace containing the clone of this package. 18 | -------------------------------------------------------------------------------- /yumi/gazebo_mimic/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package gazebo_mimic 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 0.0.4 (2017-01-12) 6 | ------------------ 7 | 8 | 0.0.2 (2017-01-10) 9 | ------------------ 10 | * fix for backcompatibility with gazebo 11 | * the mimic plugin that we probably forgot to commit long time ago 12 | * Contributors: Todor Stoyanov 13 | -------------------------------------------------------------------------------- /yumi/gazebo_mimic/README.md: -------------------------------------------------------------------------------- 1 | Controllers for the Velvet Fingers 2 gripper. The gazebo_mimic_plugin was adapted from Gonçalo Cabrita (original at: https://github.com/ras-sight/hratc2015_framework) in order to have Gazebo support the mimic open/close joint of the gripper. AFAIK, starting at Gazebo 3.0 there should be native support and this plugin should be obsolete ... 2 | -------------------------------------------------------------------------------- /yumi/gazebo_mimic/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | gazebo_mimic 4 | 0.0.4 5 | The gazebo_mimic package 6 | 7 | Yoshua Nava 8 | 9 | BSD 10 | 11 | Robert Krug 12 | 13 | catkin 14 | gazebo_ros 15 | 16 | controller_manager 17 | gazebo_ros 18 | gazebo_ros_control 19 | gazebo_plugins 20 | robot_state_publisher 21 | ros_control 22 | ros_controllers 23 | 24 | 25 | 26 | 27 | 28 | -------------------------------------------------------------------------------- /yumi/yumi_moveit_config/.setup_assistant: -------------------------------------------------------------------------------- 1 | moveit_setup_assistant_config: 2 | URDF: 3 | package: yumi_description 4 | relative_path: urdf/yumi.urdf 5 | SRDF: 6 | relative_path: config/yumi.srdf 7 | CONFIG: 8 | author_name: Yoshua Nava 9 | author_email: yoshua@kth.se 10 | generated_timestamp: 1500457566 -------------------------------------------------------------------------------- /yumi/yumi_moveit_config/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package yumi_moveit_config 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 0.0.4 (2017-01-12) 6 | ------------------ 7 | 8 | 0.0.2 (2017-01-10) 9 | ------------------ 10 | * moveit support for yumi with trajectory downloading using industrial abb drivers 11 | * added chomp interfaces 12 | * Contributors: Todor Stoyanov 13 | -------------------------------------------------------------------------------- /yumi/yumi_moveit_config/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(yumi_moveit_config) 3 | 4 | find_package(catkin REQUIRED) 5 | 6 | catkin_package() 7 | 8 | install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) 9 | install(DIRECTORY config DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) 10 | -------------------------------------------------------------------------------- /yumi/yumi_moveit_config/config/kinematics.yaml: -------------------------------------------------------------------------------- 1 | left_arm: 2 | kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin 3 | kinematics_solver_search_resolution: 0.005 4 | kinematics_solver_timeout: 0.005 5 | kinematics_solver_attempts: 3 6 | right_arm: 7 | kinematics_solver: kdl_kinematics_plugin/KDLKinematicsPlugin 8 | kinematics_solver_search_resolution: 0.005 9 | kinematics_solver_timeout: 0.005 10 | kinematics_solver_attempts: 3 -------------------------------------------------------------------------------- /yumi/yumi_moveit_config/launch/default_warehouse_db.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | -------------------------------------------------------------------------------- /yumi/yumi_moveit_config/launch/fake_moveit_controller_manager.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | -------------------------------------------------------------------------------- /yumi/yumi_moveit_config/launch/joystick_control.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | -------------------------------------------------------------------------------- /yumi/yumi_moveit_config/launch/moveit_rviz.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 13 | 14 | 15 | 16 | 17 | -------------------------------------------------------------------------------- /yumi/yumi_moveit_config/launch/ompl_planning_pipeline.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 8 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | -------------------------------------------------------------------------------- /yumi/yumi_moveit_config/launch/planning_pipeline.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | -------------------------------------------------------------------------------- /yumi/yumi_moveit_config/launch/run_benchmark_ompl.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | -------------------------------------------------------------------------------- /yumi/yumi_moveit_config/launch/sensor_manager.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | -------------------------------------------------------------------------------- /yumi/yumi_moveit_config/launch/setup_assistant.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 14 | 15 | 16 | -------------------------------------------------------------------------------- /yumi/yumi_moveit_config/launch/warehouse.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | -------------------------------------------------------------------------------- /yumi/yumi_moveit_config/launch/warehouse_settings.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | -------------------------------------------------------------------------------- /yumi/yumi_moveit_config/launch/yumi_moveit_controller_manager.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | -------------------------------------------------------------------------------- /yumi/yumi_moveit_config/launch/yumi_moveit_sensor_manager.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | -------------------------------------------------------------------------------- /yumi/yumi_moveit_config/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | yumi_moveit_config 4 | 0.0.4 5 | 6 | An automatically generated package with all the configuration and launch files for using the yumi with the MoveIt Motion Planning Framework 7 | 8 | Todor Stoyanov 9 | Todor Stoyanov 10 | Yoshua Nava 11 | 12 | BSD 13 | 14 | moveit_ros_move_group 15 | moveit_planners_ompl 16 | moveit_ros_visualization 17 | joint_state_publisher 18 | robot_state_publisher 19 | xacro 20 | yumi_description 21 | yumi_description 22 | 23 | 24 | catkin 25 | 26 | 27 | -------------------------------------------------------------------------------- /yumi/yumi_support/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package yumi_support 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 0.0.4 (2017-01-12) 6 | ------------------ 7 | 8 | 0.0.2 (2017-01-10) 9 | ------------------ 10 | * Initial import 11 | 12 | -------------------------------------------------------------------------------- /yumi/yumi_support/config/joint_names_left.yaml: -------------------------------------------------------------------------------- 1 | controller_joint_names: 2 | - yumi_joint_1_l 3 | - yumi_joint_2_l 4 | - yumi_joint_3_l 5 | - yumi_joint_4_l 6 | - yumi_joint_5_l 7 | - yumi_joint_6_l 8 | - yumi_joint_7_l 9 | -------------------------------------------------------------------------------- /yumi/yumi_support/config/joint_names_right.yaml: -------------------------------------------------------------------------------- 1 | controller_joint_names: 2 | - yumi_joint_1_r 3 | - yumi_joint_2_r 4 | - yumi_joint_3_r 5 | - yumi_joint_4_r 6 | - yumi_joint_5_r 7 | - yumi_joint_6_r 8 | - yumi_joint_7_r 9 | -------------------------------------------------------------------------------- /yumi/yumi_support/package.xml: -------------------------------------------------------------------------------- 1 | 2 | yumi_support 3 | 0.0.4 4 | 5 |

6 | RAPID code and launch files for the abb driver for yumi 7 |

8 |

9 | This is a modified driver from the ROS-Industrial abb driver. Main changes are for handling the 10 | two arms of YuMi in a reasonable manner. 11 | The orriginal package is part of the ROS-Industrial program and contains nodes 12 | for interfacing with ABB industrial robot controllers. 13 |

14 |
15 | Todor Stoyanov 16 | Todor Stoyanov 17 | BSD 18 | 19 | https://github.com/rktg/yumi 20 | 21 | catkin 22 | 23 | abb_driver 24 |
25 | -------------------------------------------------------------------------------- /yumi_control/launch/display_yumi_robot.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | -------------------------------------------------------------------------------- /yumi_control/launch/display_yumi_with_hands.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | -------------------------------------------------------------------------------- /yumi_description/CHANGELOG.rst: -------------------------------------------------------------------------------- 1 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 2 | Changelog for package yumi_description 3 | ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ 4 | 5 | 0.0.4 (2017-01-12) 6 | ------------------ 7 | 8 | 0.0.2 (2017-01-10) 9 | ------------------ 10 | * Add coarser meshes. 11 | * Add exec_depend on xacro. 12 | * skeleton of the yumi_description package 13 | * Contributors: Maarten de Vries, Robert Krug, Todor Stoyanov 14 | -------------------------------------------------------------------------------- /yumi_description/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(yumi_description) 3 | 4 | find_package(catkin REQUIRED) 5 | 6 | catkin_package() 7 | 8 | install( 9 | DIRECTORY gazebo launch meshes urdf 10 | DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} 11 | ) 12 | -------------------------------------------------------------------------------- /yumi_description/README.md: -------------------------------------------------------------------------------- 1 | The joint numbering for each arm follows ABB's strange convention, namely (in physical order starting with the joint connecting to the body): 1, 2, 7, 3, 4, 5, 6 2 | -------------------------------------------------------------------------------- /yumi_description/meshes/body.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/yumi_description/meshes/body.stl -------------------------------------------------------------------------------- /yumi_description/meshes/coarse/.gitignore: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/yumi_description/meshes/coarse/.gitignore -------------------------------------------------------------------------------- /yumi_description/meshes/coarse/body.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/yumi_description/meshes/coarse/body.stl -------------------------------------------------------------------------------- /yumi_description/meshes/coarse/link_1.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/yumi_description/meshes/coarse/link_1.stl -------------------------------------------------------------------------------- /yumi_description/meshes/coarse/link_2.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/yumi_description/meshes/coarse/link_2.stl -------------------------------------------------------------------------------- /yumi_description/meshes/coarse/link_3.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/yumi_description/meshes/coarse/link_3.stl -------------------------------------------------------------------------------- /yumi_description/meshes/coarse/link_4.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/yumi_description/meshes/coarse/link_4.stl -------------------------------------------------------------------------------- /yumi_description/meshes/coarse/link_5.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/yumi_description/meshes/coarse/link_5.stl -------------------------------------------------------------------------------- /yumi_description/meshes/coarse/link_6.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/yumi_description/meshes/coarse/link_6.stl -------------------------------------------------------------------------------- /yumi_description/meshes/coarse/link_7.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/yumi_description/meshes/coarse/link_7.stl -------------------------------------------------------------------------------- /yumi_description/meshes/gripper/base.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/yumi_description/meshes/gripper/base.stl -------------------------------------------------------------------------------- /yumi_description/meshes/gripper/coarse/base.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/yumi_description/meshes/gripper/coarse/base.stl -------------------------------------------------------------------------------- /yumi_description/meshes/gripper/coarse/finger.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/yumi_description/meshes/gripper/coarse/finger.stl -------------------------------------------------------------------------------- /yumi_description/meshes/gripper/finger.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/yumi_description/meshes/gripper/finger.stl -------------------------------------------------------------------------------- /yumi_description/meshes/link_1.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/yumi_description/meshes/link_1.stl -------------------------------------------------------------------------------- /yumi_description/meshes/link_2.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/yumi_description/meshes/link_2.stl -------------------------------------------------------------------------------- /yumi_description/meshes/link_3.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/yumi_description/meshes/link_3.stl -------------------------------------------------------------------------------- /yumi_description/meshes/link_4.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/yumi_description/meshes/link_4.stl -------------------------------------------------------------------------------- /yumi_description/meshes/link_5.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/yumi_description/meshes/link_5.stl -------------------------------------------------------------------------------- /yumi_description/meshes/link_6.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/yumi_description/meshes/link_6.stl -------------------------------------------------------------------------------- /yumi_description/meshes/link_7.stl: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/liangyuwei/sign_language_robot/b15649a73272e2883d8d5b1b22de1fc4095b43ec/yumi_description/meshes/link_7.stl -------------------------------------------------------------------------------- /yumi_description/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | yumi_description 4 | 0.0.4 5 | The yumi_description package 6 | 7 | Yoshua Nava 8 | 9 | BSD 10 | 11 | Robert Krug 12 | 13 | catkin 14 | xacro 15 | 16 | -------------------------------------------------------------------------------- /yumi_description/urdf/Gazebo/gazebo.urdf.xacro: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | /yumi 7 | 8 | 9 | 10 | 11 | 12 | 13 | -------------------------------------------------------------------------------- /yumi_description/urdf/Gazebo/yumi.gazebo.xacro: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | Gazebo/Ivory 10 | 0.2 11 | 0.2 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | -------------------------------------------------------------------------------- /yumi_description/urdf/Grippers/yumi_servo_gripper.gazebo.xacro: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | ${name}_joint 11 | ${name}_joint_m 12 | 1.0 13 | 14 | 15 | 16 | 17 | 18 | Gazebo/Light_Grey 19 | 0.2 20 | 0.2 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | -------------------------------------------------------------------------------- /yumi_description/urdf/Grippers/yumi_servo_gripper.transmission.xacro: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | transmission_interface/SimpleTransmission 8 | 9 | ${hardware_interface} 10 | 11 | 12 | ${hardware_interface} 13 | 1 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | -------------------------------------------------------------------------------- /yumi_description/urdf/Util/materials.xacro: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | 19 | 20 | 21 | 22 | 23 | 24 | 25 | 26 | 27 | 28 | 29 | 30 | 31 | 32 | 33 | 34 | 35 | 36 | 37 | 38 | 39 | 40 | 41 | 42 | 43 | 44 | 45 | -------------------------------------------------------------------------------- /yumi_sign_language_robot_control/package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | yumi_sign_language_robot_control 4 | 0.0.0 5 | The sign_language_robot_control package 6 | 7 | liangyuwei 8 | 9 | TODO 10 | 11 | 12 | roscpp 13 | shape_msgs 14 | moveit_msgs 15 | geometry_msgs 16 | kdl_parser 17 | 18 | kdl_parser 19 | 20 | 21 | catkin 22 | 23 | 24 | 25 | 26 | -------------------------------------------------------------------------------- /yumi_sign_language_robot_moveit_config/.setup_assistant: -------------------------------------------------------------------------------- 1 | moveit_setup_assistant_config: 2 | URDF: 3 | package: yumi_description 4 | relative_path: urdf/yumi_with_hands.urdf 5 | xacro_args: "--inorder " 6 | SRDF: 7 | relative_path: config/yumi.srdf 8 | CONFIG: 9 | author_name: Yuwei Liang 10 | author_email: lyw.liangyuwei@gmail.com 11 | generated_timestamp: 1601006962 -------------------------------------------------------------------------------- /yumi_sign_language_robot_moveit_config/CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.3) 2 | project(yumi_sign_language_robot_moveit_config) 3 | 4 | find_package(catkin REQUIRED) 5 | 6 | catkin_package() 7 | 8 | install(DIRECTORY launch DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} 9 | PATTERN "setup_assistant.launch" EXCLUDE) 10 | install(DIRECTORY config DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}) 11 | -------------------------------------------------------------------------------- /yumi_sign_language_robot_moveit_config/config/chomp_planning.yaml: -------------------------------------------------------------------------------- 1 | planning_time_limit: 10.0 2 | max_iterations: 200 3 | max_iterations_after_collision_free: 5 4 | smoothness_cost_weight: 0.1 5 | obstacle_cost_weight: 1.0 6 | learning_rate: 0.01 7 | smoothness_cost_velocity: 0.0 8 | smoothness_cost_acceleration: 1.0 9 | smoothness_cost_jerk: 0.0 10 | ridge_factor: 0.01 11 | use_pseudo_inverse: false 12 | pseudo_inverse_ridge_factor: 1e-4 13 | joint_update_limit: 0.1 14 | collision_clearence: 0.2 15 | collision_threshold: 0.07 16 | use_stochastic_descent: true 17 | enable_failure_recovery: true 18 | max_recovery_attempts: 5 -------------------------------------------------------------------------------- /yumi_sign_language_robot_moveit_config/config/sensors_3d.yaml: -------------------------------------------------------------------------------- 1 | # The name of this file shouldn't be changed, or else the Setup Assistant won't detect it 2 | sensors: 3 | - filtered_cloud_topic: filtered_cloud 4 | max_range: 5.0 5 | max_update_rate: 1.0 6 | padding_offset: 0.1 7 | padding_scale: 1.0 8 | point_cloud_topic: /head_mount_kinect/depth_registered/points 9 | point_subsample: 1 10 | sensor_plugin: occupancy_map_monitor/PointCloudOctomapUpdater -------------------------------------------------------------------------------- /yumi_sign_language_robot_moveit_config/launch/chomp_planning_pipeline.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | -------------------------------------------------------------------------------- /yumi_sign_language_robot_moveit_config/launch/default_warehouse_db.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | -------------------------------------------------------------------------------- /yumi_sign_language_robot_moveit_config/launch/fake_moveit_controller_manager.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | -------------------------------------------------------------------------------- /yumi_sign_language_robot_moveit_config/launch/joystick_control.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | -------------------------------------------------------------------------------- /yumi_sign_language_robot_moveit_config/launch/moveit_rviz.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 13 | 14 | 15 | 16 | 17 | -------------------------------------------------------------------------------- /yumi_sign_language_robot_moveit_config/launch/planning_pipeline.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | -------------------------------------------------------------------------------- /yumi_sign_language_robot_moveit_config/launch/ros_controllers.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 10 | 11 | 12 | -------------------------------------------------------------------------------- /yumi_sign_language_robot_moveit_config/launch/sensor_manager.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | 18 | -------------------------------------------------------------------------------- /yumi_sign_language_robot_moveit_config/launch/setup_assistant.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 14 | 15 | 16 | -------------------------------------------------------------------------------- /yumi_sign_language_robot_moveit_config/launch/warehouse.launch: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | -------------------------------------------------------------------------------- /yumi_sign_language_robot_moveit_config/launch/warehouse_settings.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | 12 | 13 | 14 | 15 | 16 | 17 | -------------------------------------------------------------------------------- /yumi_sign_language_robot_moveit_config/launch/yumi_moveit_controller_manager.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 5 | 6 | 7 | 8 | 9 | 10 | 11 | -------------------------------------------------------------------------------- /yumi_sign_language_robot_moveit_config/launch/yumi_moveit_sensor_manager.launch.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | 4 | --------------------------------------------------------------------------------