Skip to content
Snippets Groups Projects

Compare revisions

Changes are shown as if the source revision was being merged into the target revision. Learn more about comparing revisions.

Source

Select target project
No results found
Select Git revision

Target

Select target project
  • gut-teaching/introduction-to-robotics/introduction-to-robotics
  • florian.becker.dus/introduction-to-robotics
  • mohildenraaz/introduction-to-robotics
  • max.huthmacher/introduction-to-robotics
  • madhavapandiyan26/introduction-to-robotics
  • beckerst99/introduction-to-robotics
  • gohari_mojdeh/introduction-to-robotics
7 results
Select Git revision
Show changes
Commits on Source (13)
Showing
with 2140 additions and 1 deletion
......@@ -2,3 +2,10 @@ sol_*
.ipynb_*
.DS_STORE*
map.*
.vscode/
Exercises/catkin_ws/.catkin_tools/*
Exercises/catkin_ws/build/*
Exercises/catkin_ws/devel/*
Exercises/catkin_ws/logs/*
Exercises/catkin_ws/CMakeLists.txt
\ No newline at end of file
cmake_minimum_required(VERSION 3.1.3)
project(arm_robot)
find_package(catkin REQUIRED COMPONENTS
roscpp
rospy
std_msgs
message_generation
geometry_msgs
urdf
xacro
)
catkin_package(
CATKIN_DEPENDS
message_runtime
geometry_msgs
roscpp
rospy
std_msgs
)
find_package(roslaunch)
foreach(dir config launch meshes urdf)
install(DIRECTORY ${dir}/
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/${dir})
endforeach(dir)
controller_joint_names: ['', 'joint1', 'joint2', 'joint3', 'joint4', 'virtual_roll_joint', 'virtual_yaw_joint', 'joint5', 'joint6', ]
gripper_group_controller:
type: "position_controllers/JointTrajectoryController"
joints: [joint5, joint6]
joint_state_controller:
type: "joint_state_controller/JointStateController"
publish_rate: 50
arm_group_controller:
type: "effort_controllers/JointTrajectoryController"
joints:
- joint1
- joint2
- joint3
- joint4
- virtual_roll_joint
- virtual_yaw_joint
constraints:
goal_time: 0.5 # Override default
stopped_velocity_tolerance: 0.02 # Override default
joint1:
trajectory: 0.05 # Not enforced if unspecified
goal: 0.02 # Not enforced if unspecified
joint2:
trajectory: 0.05 # Not enforced if unspecified
goal: 0.02 # Not enforced if unspecified
joint3:
trajectory: 0.05 # Not enforced if unspecified
goal: 0.02 # Not enforced if unspecified
joint4:
trajectory: 0.05 # Not enforced if unspecified
goal: 0.02 # Not enforced if unspecified
virtual_roll_joint:
trajectory: 0.05 # Not enforced if unspecified
goal: 0.02 # Not enforced if unspecified
virtual_yaw_joint:
trajectory: 0.05 # Not enforced if unspecified
goal: 0.02 # Not enforced if unspecified
gains: # Required because we're controlling an effort interface
joint1: {p: 50, d: 0.01, i: 0, i_clamp: 1}
joint2: {p: 100, d: 0.01, i: 0, i_clamp: 1}
joint3: {p: 100, d: 0.01, i: 0, i_clamp: 1}
joint4: {p: 100, d: 0.01, i: 0, i_clamp: 1}
virtual_roll_joint: {p: 100, d: 0.01, i: 0, i_clamp: 1}
virtual_yaw_joint: {p: 100, d: 0.01, i: 0, i_clamp: 1}
This diff is collapsed.
<launch>
<arg name="arg_x" default="0.00" />
<arg name="arg_y" default="0.00" />
<arg name="arg_z" default="0.00" />
<arg name="arg_R" default="0.00" />
<arg name="arg_P" default="0.00" />
<arg name="arg_Y" default="0.00" />
<!--Urdf
file path-->
<param name="robot_description" textfile="$(find arm_robot)/urdf/arm_robot.urdf" />
<!--spawn
a empty gazebo world-->
<include file="$(find gazebo_ros)/launch/empty_world.launch" >
<arg name="world_name" value="$(find arm_robot)/worlds/empty.world" />
<arg name="paused" value="true" />
<arg name="use_sim_time" value="true" />
</include>
<node name="tf_footprint_base" pkg="tf" type="static_transform_publisher"
args="0 0 0 0 0 0 base_link base_footprint 40" />
<!--spawn
model-->
<node name="spawn_urdf" pkg="gazebo_ros" type="spawn_model"
args="-x $(arg arg_x) -y $(arg arg_y) -z $(arg arg_z) -Y $(arg arg_Y) -param robot_description -urdf -model arm_robot
-J joint1 0.0 -J joint2 0.0 -J joint3 0.73 -J joint4 1.07 -J joint5 0.0 -J joint6 0.0 -unpause" />
<!--Load
and launch the joint trajectory controller-->
<rosparam file="$(find arm_robot)/config/joint_trajectory_controller.yaml" command="load" />
<node name="controller_spawner" pkg="controller_manager" type="spawner" respawn="false"
output="screen" args="joint_state_controller arm_group_controller gripper_group_controller" />
<!-- Robot State Publisher for TF of each joint: publishes all the current states of the joint,
then RViz can visualize -->
<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher"
respawn="false" output="screen" />
</launch>
\ No newline at end of file
<launch>
<arg
name="model" />
<param
name="robot_description"
textfile="$(find arm_robot)/urdf/arm_robot.urdf" />
<node
name="joint_state_publisher_gui"
pkg="joint_state_publisher_gui"
type="joint_state_publisher_gui" />
<node
name="robot_state_publisher"
pkg="robot_state_publisher"
type="robot_state_publisher" />
<node
name="rviz"
pkg="rviz"
type="rviz"
args="-d $(find arm_robot)/urdf.rviz" />
</launch>
\ No newline at end of file
<launch>
<include
file="$(find gazebo_ros)/launch/empty_world.launch" />
<node
name="tf_footprint_base"
pkg="tf"
type="static_transform_publisher"
args="0 0 0 0 0 0 base_link base_footprint 40" />
<node
name="spawn_model"
pkg="gazebo_ros"
type="spawn_model"
args="-file $(find arm_robot)/urdf/arm_robot.urdf -urdf -model arm_robot"
output="screen" />
<node
name="fake_joint_calibration"
pkg="rostopic"
type="rostopic"
args="pub /calibrated std_msgs/Bool true" />
</launch>
\ No newline at end of file
File added
File added
File added
File added
File added
File added
File added
<package format="2">
<name>arm_robot</name>
<version>1.0.0</version>
<description>
<p>URDF Description package for arm_robot</p>
<p>This package contains configuration data, 3D models and launch files
for arm_robot robot</p>
</description>
<author>A Das</author>
<maintainer email="abhirup.das@rwth-aachen.de" />
<license>BSD</license>
<buildtool_depend>catkin</buildtool_depend>
<build_depend>roscpp</build_depend>
<build_depend>rospy</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>geometry_msgs</build_depend>
<build_depend>urdf</build_depend>
<build_depend>xacro</build_depend>
<build_depend>message_generation</build_depend>
<depend>roslaunch</depend>
<depend>robot_state_publisher</depend>
<depend>rviz</depend>
<depend>joint_state_publisher</depend>
<depend>joint_state_publisher_gui</depend>
<depend>gazebo</depend>
<depend>moveit_simple_controller_manager</depend>
<build_export_depend>roscpp</build_export_depend>
<build_export_depend>rospy</build_export_depend>
<build_export_depend>std_msgs</build_export_depend>
<build_export_depend>geometry_msgs</build_export_depend>
<build_export_depend>urdf</build_export_depend>
<build_export_depend>xacro</build_export_depend>
<build_export_depend>message_generation</build_export_depend>
<exec_depend>roscpp</exec_depend>
<exec_depend>rospy</exec_depend>
<exec_depend>std_msgs</exec_depend>
<exec_depend>geometry_msgs</exec_depend>
<exec_depend>urdf</exec_depend>
<exec_depend>xacro</exec_depend>
<exec_depend>message_runtime</exec_depend>
<export>
<architecture_independent />
</export>
</package>
Panels:
- Class: rviz/Displays
Help Height: 78
Name: Displays
Property Tree Widget:
Expanded:
- /Global Options1
- /Status1
- /TF1
- /TF1/Frames1
Splitter Ratio: 0.5
Tree Height: 549
- Class: rviz/Selection
Name: Selection
- Class: rviz/Tool Properties
Expanded:
- /2D Pose Estimate1
- /2D Nav Goal1
- /Publish Point1
Name: Tool Properties
Splitter Ratio: 0.5886790156364441
- Class: rviz/Views
Expanded:
- /Current View1
Name: Views
Splitter Ratio: 0.5
- Class: rviz/Time
Name: Time
SyncMode: 0
SyncSource: ""
Preferences:
PromptSaveOnExit: true
Toolbars:
toolButtonStyle: 2
Visualization Manager:
Class: ""
Displays:
- Alpha: 0.5
Cell Size: 1
Class: rviz/Grid
Color: 160; 160; 164
Enabled: true
Line Style:
Line Width: 0.029999999329447746
Value: Lines
Name: Grid
Normal Cell Count: 0
Offset:
X: 0
Y: 0
Z: 0
Plane: XY
Plane Cell Count: 10
Reference Frame: <Fixed Frame>
Value: true
- Alpha: 1
Class: rviz/RobotModel
Collision Enabled: false
Enabled: true
Links:
All Links Enabled: true
Expand Joint Details: false
Expand Link Details: false
Expand Tree: false
Link Tree Style: Links in Alphabetic Order
base_link:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
gripper_center:
Alpha: 1
Show Axes: false
Show Trail: false
link1:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link2:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link3:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link4:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link5:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
link6:
Alpha: 1
Show Axes: false
Show Trail: false
Value: true
world:
Alpha: 1
Show Axes: false
Show Trail: false
Name: RobotModel
Robot Description: robot_description
TF Prefix: ""
Update Interval: 0
Value: true
Visual Enabled: true
- Class: rviz/TF
Enabled: true
Filter (blacklist): ""
Filter (whitelist): ""
Frame Timeout: 15
Frames:
All Enabled: false
base_link:
Value: false
gripper_center:
Value: true
link1:
Value: false
link2:
Value: false
link3:
Value: false
link4:
Value: true
link5:
Value: false
link6:
Value: false
world:
Value: false
Marker Alpha: 1
Marker Scale: 1
Name: TF
Show Arrows: true
Show Axes: true
Show Names: true
Tree:
world:
base_link:
link1:
link2:
link3:
link4:
gripper_center:
{}
link5:
{}
link6:
{}
Update Interval: 0
Value: true
Enabled: true
Global Options:
Background Color: 48; 48; 48
Default Light: true
Fixed Frame: world
Frame Rate: 30
Name: root
Tools:
- Class: rviz/Interact
Hide Inactive Objects: true
- Class: rviz/MoveCamera
- Class: rviz/Select
- Class: rviz/FocusCamera
- Class: rviz/Measure
- Class: rviz/SetInitialPose
Theta std deviation: 0.2617993950843811
Topic: /initialpose
X std deviation: 0.5
Y std deviation: 0.5
- Class: rviz/SetGoal
Topic: /move_base_simple/goal
- Class: rviz/PublishPoint
Single click: true
Topic: /clicked_point
Value: true
Views:
Current:
Class: rviz/Orbit
Distance: 0.445334255695343
Enable Stereo Rendering:
Stereo Eye Separation: 0.05999999865889549
Stereo Focal Distance: 1
Swap Stereo Eyes: false
Value: false
Field of View: 0.7853981852531433
Focal Point:
X: 0.2058536857366562
Y: 0.0014365644892677665
Z: 0.34997329115867615
Focal Shape Fixed Size: true
Focal Shape Size: 0.05000000074505806
Invert Z Axis: false
Name: Current View
Near Clip Distance: 0.009999999776482582
Pitch: 0.36039838194847107
Target Frame: <Fixed Frame>
Yaw: 3.0803983211517334
Saved:
- Class: rviz/Orbit
Distance: 0.445334255695343
Enable Stereo Rendering:
Stereo Eye Separation: 0.05999999865889549
Stereo Focal Distance: 1
Swap Stereo Eyes: false
Value: false
Field of View: 0.7853981852531433
Focal Point:
X: 0.2058536857366562
Y: 0.0014365644892677665
Z: 0.34997329115867615
Focal Shape Fixed Size: true
Focal Shape Size: 0.05000000074505806
Invert Z Axis: false
Name: Orbit
Near Clip Distance: 0.009999999776482582
Pitch: 0.36039838194847107
Target Frame: <Fixed Frame>
Yaw: 3.0803983211517334
Window Geometry:
Displays:
collapsed: false
Height: 846
Hide Left Dock: false
Hide Right Dock: false
QMainWindow State: 000000ff00000000fd000000040000000000000156000002b0fc0200000008fb0000001200530065006c0065006300740069006f006e00000001e10000009b0000005c00fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000003d000002b0000000c900fffffffb0000002000730065006c0065006300740069006f006e00200062007500660066006500720200000138000000aa0000023a00000294fb00000014005700690064006500530074006500720065006f02000000e6000000d2000003ee0000030bfb0000000c004b0069006e0065006300740200000186000001060000030c00000261000000010000010f000002b0fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000003d000002b0000000a400fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e10000019700000003000004b00000003efc0100000002fb0000000800540069006d00650100000000000004b0000003bc00fffffffb0000000800540069006d006501000000000000045000000000000000000000023f000002b000000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000
Selection:
collapsed: false
Time:
collapsed: false
Tool Properties:
collapsed: false
Views:
collapsed: false
Width: 1200
X: 60
Y: 27
Link Name,Center of Mass X,Center of Mass Y,Center of Mass Z,Center of Mass Roll,Center of Mass Pitch,Center of Mass Yaw,Mass,Moment Ixx,Moment Ixy,Moment Ixz,Moment Iyy,Moment Iyz,Moment Izz,Visual X,Visual Y,Visual Z,Visual Roll,Visual Pitch,Visual Yaw,Mesh Filename,Color Red,Color Green,Color Blue,Color Alpha,Collision X,Collision Y,Collision Z,Collision Roll,Collision Pitch,Collision Yaw,Collision Mesh Filename,Material Name,SW Components,Coordinate System,Axis Name,Joint Name,Joint Type,Joint Origin X,Joint Origin Y,Joint Origin Z,Joint Origin Roll,Joint Origin Pitch,Joint Origin Yaw,Parent,Joint Axis X,Joint Axis Y,Joint Axis Z,Limit Effort,Limit Velocity,Limit Lower,Limit Upper,Calibration rising,Calibration falling,Dynamics Damping,Dynamics Friction,Safety Soft Upper,Safety Soft Lower,Safety K Position,Safety K Velocity
base_link,-0.00013508,0.021215,0.0003347,0,0,0,0.85623,0.0025365,-3.3034E-08,1.1719E-06,0.0050308,8.1853E-08,0.0025341,0,0,0,0,0,0,package://arm_robot/meshes/base_link.STL,0.79216,0.81961,0.93333,1,0,0,0,0,0,0,package://arm_robot/meshes/base_link.STL,,big_base-1,base_attachment-2,Part 1-1,base_attachment-3,base_attachment-1,mg995.stp-4,Part 3-1,new org,,,,0,0,0,0,0,0,,0,0,0,,,,,,
link1,0.0001723,0.010717,0.0033,0,0,0,0.17559,0.00017251,1.0427E-06,8.7306E-07,0.00031357,-2.0249E-06,0.00015248,0,0,0,0,0,0,package://arm_robot/meshes/link1.STL,0.79216,0.81961,0.93333,1,0,0,0,0,0,0,package://arm_robot/meshes/link1.STL,,robot_painter_02-arm motor clamp-1-solid1_rev-1,mg995.stp-3,twisting_link_base-1,Origin_joint1,Axis1,joint1,revolute,0,0.0653,0,0,1.4664,0,base_link,0,1,0,3,3,0,3.142,,,,,,
link2,0.0028854,-0.037657,0.02116,0,0,0,0.029075,3.2099E-05,-3.0364E-09,1.3417E-09,8.7678E-06,1.2187E-05,2.3608E-05,0,0,0,0,0,0,package://arm_robot/meshes/link2.STL,0.79216,0.81961,0.93333,1,0,0,0,0,0,0,package://arm_robot/meshes/link2.STL,,robot_painter_02-a1_2_painter-1-solid1-1,robot_painter_02-Circle-1-solid1-2,robot_painter_02-a1_painter-1-solid1-1,robot_painter_02-Circle-1-solid1-1,Origin_joint2,Axis2,joint2,revolute,0,0.0229,0.00043961,0.51193,0,3.1416,link1,-1,0,0,3,3,-1.57,1.57,,,,,
link3,0.039018,-1.5837E-05,0.00013351,0,0,0,0.077386,8.8164E-06,6.2986E-08,-1.6053E-06,6.4568E-05,-4.7787E-10,6.301E-05,0,0,0,0,0,0,package://arm_robot/meshes/link3.STL,0.79216,0.81961,0.93333,1,0,0,0,0,0,0,package://arm_robot/meshes/link3.STL,,mg995.stp-2,robot_painter_02-a2_2PRA-1-solid1-1,robot_painter_02-a2_1PRA-1-solid1-1,robot_painter_02-Circle-1-solid1-3,Origin_joint3,Axis3,joint3,revolute,0,-0.075315,0.042319,1.5708,-0.51193,-1.5708,link2,0,0,1,3,3,-1.57,1.57,,,,,
link4,0.075718,0.0078323,-0.0023511,0,0,0,0.12848,3.7512E-05,-2.5961E-08,3.1447E-06,5.7704E-05,-9.6946E-09,3.5473E-05,0,0,0,0,0,0,package://arm_robot/meshes/link4.STL,0.79216,0.81961,0.93333,1,0,0,0,0,0,0,package://arm_robot/meshes/link4.STL,,mg995.stp-1,robot_painter_02-a3_PRA-1-solid1-1,gripper_wrist-1,gripper_upper_palm-1,gripper_lower_palm-1,mg995.stp-5,Origin_joint4,Axis4,joint4,revolute,0.1181,0,0,0,0,0,link3,0,0,1,3,3,-1.57,1.57,,,
link5,0.027123,0.00037494,0.039116,0,0,0,0.01684,4.0476E-06,-6.256E-08,-2.0534E-06,5.368E-06,-1.0318E-07,1.9876E-06,0,0,0,0,0,0,package://arm_robot/meshes/link5.STL,0.79216,0.81961,0.93333,1,0,0,0,0,0,0,package://arm_robot/meshes/link5.STL,,robot_painter_02-Gripper_Assembly-gen-pt4-1,robot_painter_02-Gripper_Assembly-finger_pt1-1,robot_painter_02-Gripper_Assembly-gen-pt1-1,Origin_joint5,Axis5,joint5,revolute,0.11993,0,0.012424,-3.1112,-0.89161,0,link4,0,1,0,1,3,0,1.57,,,,,,
link6,-0.023433,8.3598E-05,0.030623,0,0,0,0.021692,4.4063E-06,7.7606E-08,2.5426E-06,6.5097E-06,-1.1332E-07,2.7995E-06,0,0,0,0,0,0,package://arm_robot/meshes/link6.STL,0.79216,0.81961,0.93333,1,0,0,0,0,0,0,package://arm_robot/meshes/link6.STL,,robot_painter_02-Gripper_Assembly-gen-pt2-1,robot_painter_02-Gripper_Assembly-gen-pt3-1,robot_painter_02-Gripper_Assembly-finger_pt2-1,Origin_joint6,Axis6,joint6,revolute,0.11993,0,-0.015576,0.030391,-0.81089,-3.1416,link4,0,1,0,1,3,-1.57,0,,,,,,
<?xml version="1.0" encoding="utf-8"?>
<!-- This URDF was automatically created by SolidWorks to URDF Exporter! Originally created by
Stephen Brawner (brawner@gmail.com)
Commit Version: 1.6.0-4-g7f85cfe Build Version: 1.6.7995.38578
For more information, please see http://wiki.ros.org/sw_urdf_exporter -->
<robot
name="arm_robot">
<link name="world" />
<link
name="base_link">
<inertial>
<origin
xyz="-0.00013508 0.021215 0.0003347"
rpy="0 0 0" />
<mass
value="0.85623" />
<inertia
ixx="0.0025365"
ixy="-3.3034E-08"
ixz="1.1719E-06"
iyy="0.0050308"
iyz="8.1853E-08"
izz="0.0025341" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://arm_robot/meshes/base_link.STL" />
</geometry>
<material
name="">
<color
rgba="0.79216 0.81961 0.93333 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://arm_robot/meshes/base_link.STL" />
</geometry>
</collision>
</link>
<joint name="base_joint" type="fixed">
<parent link="world" />
<child link="base_link" />
<origin xyz="0.0 0.0 0.0" rpy="1.57 0 0" />
</joint>
<link
name="link1">
<inertial>
<origin
xyz="0.0001723 0.010717 0.0033"
rpy="0 0 0" />
<mass
value="0.17559" />
<inertia
ixx="0.00017251"
ixy="1.0427E-06"
ixz="8.7306E-07"
iyy="0.00031357"
iyz="-2.0249E-06"
izz="0.00015248" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://arm_robot/meshes/link1.STL" />
</geometry>
<material
name="">
<color
rgba="0.79216 0.81961 0.93333 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://arm_robot/meshes/link1.STL" />
</geometry>
</collision>
</link>
<joint
name="joint1"
type="revolute">
<origin
xyz="0 0.0653 0"
rpy="0 1.4664 0" />
<parent
link="base_link" />
<child
link="link1" />
<axis
xyz="0 1 0" />
<limit
lower="0"
upper="3.142"
effort="3"
velocity="4" />
</joint>
<link
name="link2">
<inertial>
<origin
xyz="0.0028854 -0.037657 0.02116"
rpy="0 0 0" />
<mass
value="0.029075" />
<inertia
ixx="3.2099E-05"
ixy="-3.0364E-09"
ixz="1.3417E-09"
iyy="8.7678E-06"
iyz="1.2187E-05"
izz="2.3608E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://arm_robot/meshes/link2.STL" />
</geometry>
<material
name="">
<color
rgba="0.79216 0.81961 0.93333 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://arm_robot/meshes/link2.STL" />
</geometry>
</collision>
</link>
<joint
name="joint2"
type="revolute">
<origin
xyz="0 0.0229 0.00043961"
rpy="0.51193 0 3.1416" />
<parent
link="link1" />
<child
link="link2" />
<axis
xyz="-1 0 0" />
<limit
lower="-1.57"
upper="1.57"
effort="3"
velocity="4" />
</joint>
<link
name="link3">
<inertial>
<origin
xyz="0.039018 -1.5837E-05 0.00013351"
rpy="0 0 0" />
<mass
value="0.077386" />
<inertia
ixx="8.8164E-06"
ixy="6.2986E-08"
ixz="-1.6053E-06"
iyy="6.4568E-05"
iyz="-4.7787E-10"
izz="6.301E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://arm_robot/meshes/link3.STL" />
</geometry>
<material
name="">
<color
rgba="0.79216 0.81961 0.93333 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://arm_robot/meshes/link3.STL" />
</geometry>
</collision>
</link>
<joint
name="joint3"
type="revolute">
<origin
xyz="0 -0.075315 0.042319"
rpy="1.5708 -0.51193 -1.5708" />
<parent
link="link2" />
<child
link="link3" />
<axis
xyz="0 0 1" />
<limit
lower="-1.57"
upper="1.57"
effort="3"
velocity="4" />
</joint>
<link
name="link4">
<inertial>
<origin
xyz="0.075718 0.0078323 -0.0023511"
rpy="0 0 0" />
<mass
value="0.12848" />
<inertia
ixx="3.7512E-05"
ixy="-2.5961E-08"
ixz="3.1447E-06"
iyy="5.7704E-05"
iyz="-9.6946E-09"
izz="3.5473E-05" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://arm_robot/meshes/link4.STL" />
</geometry>
<material
name="">
<color
rgba="0.79216 0.81961 0.93333 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://arm_robot/meshes/link4.STL" />
</geometry>
</collision>
</link>
<joint
name="joint4"
type="revolute">
<origin
xyz="0.1181 0 0"
rpy="0 0 0" />
<parent
link="link3" />
<child
link="link4" />
<axis
xyz="0 0 1" />
<limit
lower="-1.57"
upper="1.57"
effort="3"
velocity="4" />
</joint>
<link
name="link5">
<inertial>
<origin
xyz="0.027123 0.00037494 0.039116"
rpy="0 0 0" />
<mass
value="0.01684" />
<inertia
ixx="4.0476E-06"
ixy="-6.256E-08"
ixz="-2.0534E-06"
iyy="5.368E-06"
iyz="-1.0318E-07"
izz="1.9876E-06" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://arm_robot/meshes/link5.STL" />
</geometry>
<material
name="">
<color
rgba="0.79216 0.81961 0.93333 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://arm_robot/meshes/link5.STL" />
</geometry>
</collision>
</link>
<joint
name="joint5"
type="revolute">
<origin
xyz="0.11993 0 0.012424"
rpy="-3.1112 -0.89161 0" />
<parent
link="link4" />
<child
link="link5" />
<axis
xyz="0 1 0" />
<limit
lower="0"
upper="1.57"
effort="1"
velocity="4" />
</joint>
<link
name="link6">
<inertial>
<origin
xyz="-0.023433 8.3598E-05 0.030623"
rpy="0 0 0" />
<mass
value="0.021692" />
<inertia
ixx="4.4063E-06"
ixy="7.7606E-08"
ixz="2.5426E-06"
iyy="6.5097E-06"
iyz="-1.1332E-07"
izz="2.7995E-06" />
</inertial>
<visual>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://arm_robot/meshes/link6.STL" />
</geometry>
<material
name="">
<color
rgba="0.79216 0.81961 0.93333 1" />
</material>
</visual>
<collision>
<origin
xyz="0 0 0"
rpy="0 0 0" />
<geometry>
<mesh
filename="package://arm_robot/meshes/link6.STL" />
</geometry>
</collision>
</link>
<joint
name="joint6"
type="revolute">
<origin
xyz="0.11993 0 -0.015576"
rpy="0.030391 -0.81089 -3.1416" />
<parent
link="link4" />
<child
link="link6" />
<axis
xyz="0 1 0" />
<limit
lower="-1.57"
upper="0"
effort="1"
velocity="4" />
</joint>
<!-- Virtual roll joint -->
<joint name="virtual_roll_joint" type="revolute">
<limit lower="-3.1415" upper="3.1415" effort="54.0" velocity="4" />
<parent link="link4" />
<child link="virtual_roll_link" />
<axis xyz="1 0 0" />
<origin xyz="0.2056 0.0 0.0" rpy="0 0 0" />
<dynamics damping="0.0" friction="0.0" />
</joint>
<!-- Virtual roll link -->
<link name="virtual_roll_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<box size="0.001 0.001 0.001" />
</geometry>
</visual>
<inertial>
<origin xyz="0 0 0" />
<mass value="1.0e-03" />
<inertia ixx="1.0e-03" ixy="0.0" ixz="0.0"
iyy="1.0e-03" iyz="0.0"
izz="1.0e-03" />
</inertial>
</link>
<gazebo reference="virtual_roll_link">
</gazebo>
<!-- Virtual yaw joint -->
<joint name="virtual_yaw_joint" type="revolute">
<limit lower="-3.1415" upper="3.1415" effort="54.0" velocity="4" />
<parent link="virtual_roll_link" />
<child link="virtual_yaw_link" />
<axis xyz="0 0 1" />
<origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
<dynamics damping="0.0" friction="0.0" />
</joint>
<!-- Virtual yaw link -->
<link name="virtual_yaw_link">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<box size="0.001 0.001 0.001" />
</geometry>
</visual>
<inertial>
<origin xyz="0 0 0" />
<mass value="1.0e-03" />
<inertia ixx="1.0e-03" ixy="0.0" ixz="0.0"
iyy="1.0e-03" iyz="0.0"
izz="1.0e-03" />
</inertial>
</link>
<gazebo reference="virtual_yaw_link">
</gazebo>
<!-- end effector joint -->
<link name="gripper_center">
</link>
<joint name="gripper_center_joint" type="fixed">
<parent link="virtual_yaw_link" />
<child link="gripper_center" />
<origin xyz="0.0 0.0 0.0" rpy="-1.57 0.0 -1.57" />
</joint>
<transmission name="link1_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="joint1">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="link1_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="link2_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="joint2">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="link2_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="link3_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="joint3">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="link3_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="link4_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="joint4">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="link4_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="link5_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="joint5">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
</joint>
<actuator name="link5_motor">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="link6_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="joint6">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
</joint>
<actuator name="link6_motor">
<hardwareInterface>hardware_interface/PositionJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="virtual_roll_joint_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="virtual_roll_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="virtual_roll_joint_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<transmission name="virtual_yaw_joint_trans">
<type>transmission_interface/SimpleTransmission</type>
<joint name="virtual_yaw_joint">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
</joint>
<actuator name="virtual_yaw_joint_motor">
<hardwareInterface>hardware_interface/EffortJointInterface</hardwareInterface>
<mechanicalReduction>1</mechanicalReduction>
</actuator>
</transmission>
<gazebo>
<plugin name="control" filename="libgazebo_ros_control.so">
<robotNamespace>/</robotNamespace>
</plugin>
</gazebo>
<gazebo reference="link1">
<selfCollide>true</selfCollide>
</gazebo>
<gazebo reference="link2">
<selfCollide>true</selfCollide>
</gazebo>
<gazebo reference="link3">
<selfCollide>true</selfCollide>
</gazebo>
<gazebo reference="link4">
<selfCollide>true</selfCollide>
</gazebo>
<gazebo reference="link5">
<selfCollide>true</selfCollide>
</gazebo>
<gazebo reference="link6">
<selfCollide>true</selfCollide>
</gazebo>
</robot>
\ No newline at end of file
moveit_setup_assistant_config:
URDF:
package: arm_robot
relative_path: urdf/arm_robot.urdf
xacro_args: ""
SRDF:
relative_path: config/arm_robot.srdf
CONFIG:
author_name: Abhirup Das
author_email: abhirup.das@rwth-aachen.de
generated_timestamp: 1736878867
\ No newline at end of file