Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

update urdf #71

Open
wants to merge 5 commits into
base: master
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
5 changes: 5 additions & 0 deletions dxl_armed_turtlebot/launch/dxl_armed_turtlebot_bringup.launch
Original file line number Diff line number Diff line change
Expand Up @@ -15,6 +15,11 @@
<include file="$(find turtlebot_bringup)/launch/3dsensor.launch">
<arg name="3d_sensor" default="kinect" />
</include>

<!-- robot_description is defined in minimal.launch and hope this line overwrite that-->
<arg name="model" value="$(find dxl_armed_turtlebot)/urdf/robot.urdf.xacro" />
<param name="robot_description" command="$(find xacro)/xacro.py $(arg model)" />

<include file="$(find dxl_armed_turtlebot)/launch/turtlebot_joystick_teleop.launch"
if="$(arg RUN_PS3JOY)"/>
<!-- <include file="$(find turtlebot_rviz_launchers)/launch/view_robot.launch"/> -->
Expand Down
165 changes: 120 additions & 45 deletions dxl_armed_turtlebot/urdf/dynamixel_7dof_arm.urdf.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -4,16 +4,49 @@
<xacro:include filename="$(find dynamixel_urdf)/urdf/ax12.xacro" />
<property name="M_PI" value="3.1415926535897931" />

<macro name="dynamixel_ax12_joint" params="parent name color llimit ulimit vlimit *origin" >
<joint name="${name}_joint" type="revolute">
<macro name="gripper_fixed" params="parent name color *origin">
<joint name="${name}_joint" type="fixed">
<insert_block name="origin" />
<axis xyz="0 0 1"/>
<limit effort="30" velocity="${vlimit}" lower="${llimit}" upper="${ulimit}" />
<parent link="${parent}"/>
<child link="${name}_link" />
</joint>

<link name="${name}_link">
<inertial>
<mass value="0.00001" />
<origin xyz="0 0 0" />
<inertia ixx="1.0" ixy="0.0" ixz="0.0"
iyy="1.0" iyz="0.0"
izz="1.0" />
</inertial>
<visual>
<origin xyz="0.04 0 0" rpy="0 0 0" />
<geometry>
<box size="0.08 0.01 0.030" />
</geometry>
<material name="white" />
</visual>

<collision>
<origin xyz="0.04 0.0 0.0" rpy="0 0 0" />
<geometry>
<box size="0.08 0.01 0.03"/>
</geometry>
</collision>

</link>
</macro>

<macro name="dynamixel_ax12_joint" params="parent link_name joint_name color llimit ulimit vlimit *origin" >
<joint name="${joint_name}" type="revolute">
<insert_block name="origin" />
<axis xyz="0 0 1"/>
<limit effort="30" velocity="${vlimit}" lower="${llimit}" upper="${ulimit}" />
<parent link="${parent}"/>
<child link="${link_name}" />
</joint>

<link name="${link_name}">
<inertial>
<mass value="0.00001" />
<origin xyz="0 0 0" />
Expand All @@ -37,16 +70,16 @@
</link>
</macro>

<macro name="ax12_hinge_revolute_axis" params="parent name color llimit ulimit vlimit *origin *axis">
<joint name="${name}_joint" type="revolute">
<macro name="ax12_hinge_revolute_axis" params="parent link_name joint_name color llimit ulimit vlimit *origin *axis">
<joint name="${joint_name}" type="revolute">
<insert_block name="origin" />
<insert_block name="axis" />
<limit effort="30" velocity="${vlimit}" lower="${llimit}" upper="${ulimit}" />
<parent link="${parent}"/>
<child link="${name}_link" />
<child link="${link_name}" />
</joint>

<link name="${name}_link">
<link name="${link_name}">
<inertial>
<mass value="0.00001" />
<origin xyz="0 0 0" />
Expand Down Expand Up @@ -111,58 +144,92 @@
<origin xyz="0.045 0 0.0" rpy="${M_PI} 0 0" />
</xacro:dynamixel_ax12_pan>

<xacro:ax12_hinge_revolute parent="arm_link0_link" name="arm_link1"
<xacro:ax12_hinge_revolute_axis parent="arm_link0_link" link_name="arm_link1" joint_name="arm_joint1"
llimit="-2.61" ulimit="2.61" vlimit="6.0"
color="white" >
<origin xyz="0.0 0.0 0.0" rpy="${M_PI/2} 0 ${M_PI/2}" />
</xacro:ax12_hinge_revolute>
<axis xyz="0 0 1"/>
</xacro:ax12_hinge_revolute_axis>

<xacro:dynamixel_ax12_joint parent="arm_link1_link" name="arm_link2"
<xacro:dynamixel_ax12_joint parent="arm_link1" link_name="arm_link2" joint_name="arm_joint2"
llimit="-2.61" ulimit="2.61" vlimit="6.0"
color="black" >
<origin xyz="0.0 0.0 0.05" rpy="0 0 -${M_PI/2}" />
</xacro:dynamixel_ax12_joint>

<xacro:dynamixel_ax12_tilt parent="arm_link2_link" name="arm_link2_motor" color="black">
<origin xyz="-0.06 0.0 0.02" rpy="0 0 0" />
<xacro:ax12_side_fixed parent="arm_link2" name="arm_link2_F31" color="white">
<origin xyz=" -0.039 0 0" rpy="${M_PI/2} 0 -${M_PI/2}" />
</xacro:ax12_side_fixed>

<xacro:ax12_side_fixed parent="arm_link2_F31_link" name="arm_link2_F32" color="white">
<origin xyz=" 0.0 0 0.0" rpy="${M_PI} 0 ${M_PI/2}" />
</xacro:ax12_side_fixed>

<xacro:dynamixel_ax12_tilt parent="arm_link2_F32_link" name="arm_link2_motor" color="white">
<origin xyz="0.025 0.0 -0.018" rpy="0 ${M_PI/2} 0" />
</xacro:dynamixel_ax12_tilt>

<xacro:ax12_hinge_revolute parent="arm_link2_motor_link" name="arm_link3"
<xacro:ax12_hinge_revolute_axis parent="arm_link2_motor_link" link_name="arm_link3" joint_name="arm_joint3"
llimit="-2.61" ulimit="2.61" vlimit="6.0"
color="white" >
<origin xyz="0.0 0.0 0.0" rpy="0 0 0" />
</xacro:ax12_hinge_revolute>
<origin xyz="0.0 0.0 0.0" rpy="0 0 ${M_PI}" />
<axis xyz="0 0 1"/>
</xacro:ax12_hinge_revolute_axis>

<xacro:dynamixel_ax12_pan parent="arm_link3_link" name="arm_link3_motor" color="black">
<xacro:dynamixel_ax12_pan parent="arm_link3" name="arm_link3_motor" color="black">
<origin xyz="-0.01 0.0 0.055" rpy="${M_PI} ${M_PI} 0" />
</xacro:dynamixel_ax12_pan>

<xacro:ax12_hinge_revolute_axis parent="arm_link3_motor_link" name="arm_link4"
<xacro:ax12_hinge_revolute_axis parent="arm_link3_motor_link" link_name="arm_link4" joint_name="arm_joint4"
llimit="-2.61" ulimit="2.61" vlimit="6.0"
color="white" >
<origin xyz="0.0 0.0 0.05" rpy="0 ${M_PI} 0" />
<axis xyz="0 0 1" />
</xacro:ax12_hinge_revolute_axis>

<xacro:dynamixel_ax12_joint parent="arm_link4_link" name="arm_link5"
<xacro:dynamixel_ax12_joint parent="arm_link4" link_name="arm_link5" joint_name="arm_joint5"
llimit="-2.61" ulimit="2.61" vlimit="6.0" color="black">
<origin xyz="0.0 0.0 0.0" rpy="0 -${M_PI/2} ${M_PI/2}" />
</xacro:dynamixel_ax12_joint>

<xacro:dynamixel_ax12_joint parent="arm_link5_link" name="arm_link6"
<xacro:ax12_side_fixed parent="arm_link5" name="arm_link5_F3" color="white">
<origin xyz="-0.041 0 0.0" rpy="${M_PI/2} 0 -${M_PI/2}" />
</xacro:ax12_side_fixed>


<xacro:dynamixel_ax12_joint parent="arm_link5_F3_link" link_name="arm_link6" joint_name="arm_joint6"
llimit="-2.61" ulimit="2.61" vlimit="6.0" color="black">
<origin xyz="-0.07 0.0 0.0" rpy="-${M_PI/2} ${M_PI} -${M_PI/2}" />
<origin xyz="-0.0 0.0 0.023" rpy="-0 ${M_PI} 0" />
</xacro:dynamixel_ax12_joint>

<xacro:dynamixel_ax12_pan parent="arm_link6_link" name="arm_link6_motor" color="black">
<origin xyz="0.0 0.03 -0.05" rpy="${M_PI/2} 0 ${M_PI/2}" />


<xacro:ax12_side_fixed parent="arm_link6" name="arm_link6_F3" color="white">
<origin xyz="-0.012 0 -0.025" rpy="-${M_PI} ${M_PI} ${M_PI/2}" />
</xacro:ax12_side_fixed>

<xacro:dynamixel_ax12_pan parent="arm_link6_F3_link" name="arm_link6_motor" color="black">
<origin xyz="-0.017 0.0 -0.024" rpy="${M_PI/2} 0 ${M_PI}" />
</xacro:dynamixel_ax12_pan>

<xacro:ax12_hinge_revolute parent="arm_link6_motor_link" name="arm_link7"
<xacro:ax12_hinge_revolute_axis parent="arm_link6_motor_link" link_name="arm_link7" joint_name="arm_joint7"
llimit="-2.61" ulimit="2.61" vlimit="6.0"
color="white" >
<origin xyz="0.0 0.0 0.0" rpy="${M_PI/2} 0 ${M_PI/2}" />
</xacro:ax12_hinge_revolute>
<axis xyz="0 0 1"/>
</xacro:ax12_hinge_revolute_axis>

<xacro:gripper_fixed parent="arm_link7" name="gripper" color="white">
<origin xyz="-0.06 0.0 0.032" rpy="${M_PI/2} 0 0" />
</xacro:gripper_fixed>

<xacro:ax12_side_fixed parent="arm_link6_motor_link" name="gripper_F3" color="white">
<origin xyz="-0.037 0 0" rpy="${M_PI/2} ${M_PI} ${M_PI/2}" />
</xacro:ax12_side_fixed>
<xacro:gripper_fixed parent="gripper_F3_link" name="gripper_after_F3" color="white">
<origin xyz="0 0.0 -0.02" rpy="${M_PI/2} 0 0" />
</xacro:gripper_fixed>


<!-- ros_control plugin -->
<gazebo>
Expand All @@ -177,26 +244,34 @@
</plugin>
</gazebo>

<xacro:gazebo_arm_link name="arm_base_link" color="Black" />
<xacro:gazebo_arm_link name="arm_link0_link" color="Black" />
<xacro:gazebo_arm_link name="arm_link1_link" color="Gray" />
<xacro:gazebo_arm_link name="arm_link2_link" color="Black" />
<xacro:gazebo_arm_link name="arm_link2_motor_link" color="Black" />
<xacro:gazebo_arm_link name="arm_link3_link" color="Gray" />
<xacro:gazebo_arm_link name="arm_link3_motor_link" color="Black" />
<xacro:gazebo_arm_link name="arm_link4_link" color="Gray" />
<xacro:gazebo_arm_link name="arm_link5_link" color="Black" />
<xacro:gazebo_arm_link name="arm_link6_link" color="Black" />
<xacro:gazebo_arm_link name="arm_link6_motor_link" color="Black" />
<xacro:gazebo_arm_link name="arm_link7_link" color="Gray" />

<xacro:simple_transmission name="arm_link1_joint" interface="EffortJointInterface" />
<xacro:simple_transmission name="arm_link2_joint" interface="EffortJointInterface" />
<xacro:simple_transmission name="arm_link3_joint" interface="EffortJointInterface" />
<xacro:simple_transmission name="arm_link4_joint" interface="EffortJointInterface" />
<xacro:simple_transmission name="arm_link5_joint" interface="EffortJointInterface" />
<xacro:simple_transmission name="arm_link6_joint" interface="EffortJointInterface" />
<xacro:simple_transmission name="arm_link7_joint" interface="EffortJointInterface" />
<xacro:gazebo_arm_link name="arm_base_link" color="Red" />
<xacro:gazebo_arm_link name="arm_link0_link" color="Orange" />
<xacro:gazebo_arm_link name="arm_link1" color="Yellow" />
<xacro:gazebo_arm_link name="arm_link2" color="Green" />
<xacro:gazebo_arm_link name="arm_link2_F31_link" color="Blue" />
<xacro:gazebo_arm_link name="arm_link2_F32_link" color="Purple" />
<xacro:gazebo_arm_link name="arm_link2_motor_link" color="Red" />
<xacro:gazebo_arm_link name="arm_link3" color="Orange" />
<xacro:gazebo_arm_link name="arm_link3_motor_link" color="Yellow" />
<xacro:gazebo_arm_link name="arm_link4" color="Green" />
<xacro:gazebo_arm_link name="arm_link5" color="Blue" />
<xacro:gazebo_arm_link name="arm_link5_F3_link" color="Purple" />
<xacro:gazebo_arm_link name="arm_link6" color="Red" />
<xacro:gazebo_arm_link name="arm_link6_F3_link" color="Orange" />
<xacro:gazebo_arm_link name="arm_link6_motor_link" color="Yellow" />
<xacro:gazebo_arm_link name="arm_link7" color="Green" />
<xacro:gazebo_arm_link name="gripper_link" color="Blue" />
<xacro:gazebo_arm_link name="gripper_after_F3_link" color="Purple" />
<xacro:gazebo_arm_link name="gripper_F3_link" color="Red" />
<xacro:gazebo_arm_link name="gripper_link_link" color="Gray" />

<xacro:simple_transmission name="arm_joint1" interface="EffortJointInterface" />
<xacro:simple_transmission name="arm_joint2" interface="EffortJointInterface" />
<xacro:simple_transmission name="arm_joint3" interface="EffortJointInterface" />
<xacro:simple_transmission name="arm_joint4" interface="EffortJointInterface" />
<xacro:simple_transmission name="arm_joint5" interface="EffortJointInterface" />
<xacro:simple_transmission name="arm_joint6" interface="EffortJointInterface" />
<xacro:simple_transmission name="arm_joint7" interface="EffortJointInterface" />

</xacro:macro>
</robot>
2 changes: 2 additions & 0 deletions dynamixel_7dof_arm/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -3,6 +3,8 @@ project(dynamixel_7dof_arm)

find_package(catkin REQUIRED COMPONENTS dynamixel_controllers roseus rostest) # add roseus to gen messages

catkin_python_setup()

catkin_package()

add_rostest(test/test-dxl-7dof-arm.test)
6 changes: 6 additions & 0 deletions dynamixel_7dof_arm/config/dynamixel_joint_controllers.yaml
Original file line number Diff line number Diff line change
@@ -1,3 +1,9 @@
joint_state_publisher:
controller:
package: dynamixel_7dof_arm
module: joint_state_publisher
type: JointStatePublisher

arm_j1_controller:
controller:
package: dynamixel_controllers
Expand Down
15 changes: 15 additions & 0 deletions dynamixel_7dof_arm/launch/dynamixel_7dof_arm_bringup.launch
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,21 @@
arm_j6_controller"
output="screen"/>

<node name="dynamixel_trajectory_controller_spawner_for_joint_state" pkg="dynamixel_controllers" type="controller_spawner.py"
args="--manager=dxl_manager
--port=7dof_arm_port
--type=meta
joint_state_publisher
arm_j1_controller
arm_j2_controller
arm_j3_controller
arm_j4_controller
arm_j5_controller
arm_j6_controller
arm_j7_controller
"
output="screen"/>

<!-- TODO : Should use gripper_controller_spawner.launch instead of .sh ;; timing problem -->
<node name="dynamixel_trajectory_script" pkg="dynamixel_7dof_arm" type="gripper_controller_spawner.sh" output="screen"/>
<!-- <include file="$(find dynamixel_7dof_arm)/launch/gripper_controller_spawner.launch"/> -->
Expand Down
11 changes: 11 additions & 0 deletions dynamixel_7dof_arm/setup.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,11 @@
#!/usr/bin/env python

from distutils.core import setup
from catkin_pkg.python_setup import generate_distutils_setup

d = generate_distutils_setup(
packages=['dynamixel_7dof_arm'],
package_dir={'': 'src'},
)

setup(**d)
Empty file.
Loading