Skip to content

Commit

Permalink
Merge pull request #1 from ros-industrial/kinetic-devel
Browse files Browse the repository at this point in the history
Merge kinetic-devel into personal fork
  • Loading branch information
ted-miller authored Oct 10, 2017
2 parents 1289a81 + 1ec8ca1 commit a4be1a4
Show file tree
Hide file tree
Showing 14 changed files with 171 additions and 16 deletions.
5 changes: 4 additions & 1 deletion .travis.yml
Original file line number Diff line number Diff line change
Expand Up @@ -15,12 +15,15 @@ env:
- USE_DEB=true ROS_DISTRO="indigo" ROS_REPOSITORY_PATH=http://packages.ros.org/ros-shadow-fixed/ubuntu
- USE_DEB=true ROS_DISTRO="jade" ROS_REPOSITORY_PATH=http://packages.ros.org/ros/ubuntu
- USE_DEB=true ROS_DISTRO="jade" ROS_REPOSITORY_PATH=http://packages.ros.org/ros-shadow-fixed/ubuntu
- USE_DEB=true ROS_DISTRO="kinetic" ROS_REPOSITORY_PATH=http://packages.ros.org/ros/ubuntu
- USE_DEB=true ROS_DISTRO="kinetic" ROS_REPOSITORY_PATH=http://packages.ros.org/ros-shadow-fixed/ubuntu
matrix:
allow_failures:
- env: USE_DEB=true ROS_DISTRO="indigo" ROS_REPOSITORY_PATH=http://packages.ros.org/ros/ubuntu
- env: USE_DEB=true ROS_DISTRO="indigo" ROS_REPOSITORY_PATH=http://packages.ros.org/ros-shadow-fixed/ubuntu
- env: USE_DEB=true ROS_DISTRO="jade" ROS_REPOSITORY_PATH=http://packages.ros.org/ros/ubuntu
- env: USE_DEB=true ROS_DISTRO="jade" ROS_REPOSITORY_PATH=http://packages.ros.org/ros-shadow-fixed/ubuntu
install:
- git clone https://github.com/ros-industrial/industrial_ci.git .ci_config
script:
- source .ci_config/travis.sh
# - source ./travis.sh # Enable this when you have a package-local script
20 changes: 20 additions & 0 deletions motoman_driver/launch/robot_interface_streaming_dx200.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
<!--
Contoller specific version of 'robot_interface.launch'.
Usage:
robot_interface_streaming_dx200.launch robot_ip:=<value>
-->
<launch>
<arg name="robot_ip" />
<arg name="use_bswap" default="false" />
<arg name="version0" default="true" />

<!--rosparam command="load" file="$(find motoman_config)/?" /-->

<include file="$(find motoman_driver)/launch/robot_interface_streaming.launch">
<arg name="robot_ip" value="$(arg robot_ip)" />
<arg name="use_bswap" value="$(arg use_bswap)" />
<arg name="version0" value="$(arg version0)" />
</include>
</launch>
20 changes: 20 additions & 0 deletions motoman_driver/launch/robot_interface_streaming_yrc1000.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,20 @@
<!--
Contoller specific version of 'robot_interface.launch'.
Usage:
robot_interface_streaming_yrc1000.launch robot_ip:=<value>
-->
<launch>
<arg name="robot_ip" />
<arg name="use_bswap" default="false" />
<arg name="version0" default="true" />

<!--rosparam command="load" file="$(find motoman_config)/?" /-->

<include file="$(find motoman_driver)/launch/robot_interface_streaming.launch">
<arg name="robot_ip" value="$(arg robot_ip)" />
<arg name="use_bswap" value="$(arg use_bswap)" />
<arg name="version0" value="$(arg version0)" />
</include>
</launch>
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
<!--
Multigroup, contoller specific version of 'robot_interface.launch'.
Usage:
robot_multigroup_interface_streaming_dx200.launch robot_ip:=<value>
-->
<launch>
<arg name="robot_ip" />
<arg name="use_bswap" default="false" />

<include file="$(find motoman_driver)/launch/robot_interface_streaming.launch">
<arg name="robot_ip" value="$(arg robot_ip)" />
<arg name="use_bswap" value="$(arg use_bswap)" />
<arg name="version0" value="false" />
</include>
</launch>
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
<!--
Multigroup, contoller specific version of 'robot_interface.launch'.
Usage:
robot_multigroup_interface_streaming_yrc1000.launch robot_ip:=<value>
-->
<launch>
<arg name="robot_ip" />
<arg name="use_bswap" default="false" />

<include file="$(find motoman_driver)/launch/robot_interface_streaming.launch">
<arg name="robot_ip" value="$(arg robot_ip)" />
<arg name="use_bswap" value="$(arg use_bswap)" />
<arg name="version0" value="false" />
</include>
</launch>
18 changes: 18 additions & 0 deletions motoman_driver/launch/robot_state_dx200.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
<!--
Contoller specific version of 'robot_interface.launch'.
Usage:
robot_state_dx200.launch robot_ip:=<value>
-->
<launch>
<arg name="robot_ip" />
<arg name="use_bswap" value="false" />

<!--rosparam command="load" file="$(find motoman_config)/?" /-->

<include file="$(find motoman_driver)/launch/robot_state.launch">
<arg name="robot_ip" value="$(arg robot_ip)" />
<arg name="use_bswap" value="$(arg use_bswap)" />
</include>
</launch>
18 changes: 18 additions & 0 deletions motoman_driver/launch/robot_state_yrc1000.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
<!--
Contoller specific version of 'robot_interface.launch'.
Usage:
robot_state_yrc1000.launch robot_ip:=<value>
-->
<launch>
<arg name="robot_ip" />
<arg name="use_bswap" value="false" />

<!--rosparam command="load" file="$(find motoman_config)/?" /-->

<include file="$(find motoman_driver)/launch/robot_state.launch">
<arg name="robot_ip" value="$(arg robot_ip)" />
<arg name="use_bswap" value="$(arg use_bswap)" />
</include>
</launch>
15 changes: 13 additions & 2 deletions motoman_mh5_support/urdf/mh5.urdf
Original file line number Diff line number Diff line change
Expand Up @@ -4,8 +4,10 @@
<!-- | EDITING THIS FILE BY HAND IS NOT RECOMMENDED | -->
<!-- =================================================================================== -->
<robot name="motoman_mh5" xmlns:xacro="http://ros.org/wiki/xacro">
<!-- link list -->
<link name="base_link">
<visual>
<origin rpy="0 0 3.14159"/>
<geometry>
<mesh filename="package://motoman_mh5_support/meshes/mh5/visual/MH5_BASE_AXIS.stl"/>
</geometry>
Expand All @@ -14,6 +16,7 @@
</material>
</visual>
<collision>
<origin rpy="0 0 3.14159"/>
<geometry>
<mesh filename="package://motoman_mh5_support/meshes/mh5/collision/MH5_BASE_AXIS.stl"/>
</geometry>
Expand Down Expand Up @@ -116,6 +119,8 @@
<material name="yellow"/>
</collision>
</link>
<!-- end of link list -->
<!-- joint list -->
<joint name="joint_s" type="revolute">
<parent link="base_link"/>
<child link="link_s"/>
Expand All @@ -135,7 +140,12 @@
<child link="link_u"/>
<origin rpy="0 0 0" xyz="0 0 0.3100"/>
<axis xyz="0 -1 0"/>
<limit effort="100" lower="-2.3736" upper="4.4506" velocity="2.96"/>
<!-- Old limits: lower="-2.3736" upper="4.4506" The new limits
below were measured from an MH5F. They ensure that link_r
won't hit link_l even when joint_r is at 45 degrees. The
old limits were converted directly from the MH5 data sheet,
which was clearly way off. -->
<limit effort="100" lower="-1.0122" upper="3.2218" velocity="2.96"/>
</joint>
<joint name="joint_r" type="revolute">
<parent link="link_u"/>
Expand All @@ -154,8 +164,9 @@
<joint name="joint_t" type="revolute">
<parent link="link_b"/>
<child link="link_t"/>
<origin rpy="0 0 0" xyz="0.0510 0 0"/>
<origin rpy="0 0 0" xyz="0.0865 0 0"/>
<axis xyz="-1 0 0"/>
<limit effort="100" lower="-6.2831" upper="6.2831" velocity="6.97"/>
</joint>
<!-- end of joint list -->
</robot>
2 changes: 1 addition & 1 deletion motoman_mh5_support/urdf/mh5_macro.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -161,7 +161,7 @@
<joint name="${prefix}joint_t" type="revolute">
<parent link="${prefix}link_b"/>
<child link="${prefix}link_t"/>
<origin xyz="0.0510 0 0" rpy="0 0 0"/>
<origin xyz="0.0865 0 0" rpy="0 0 0"/>
<axis xyz="-1 0 0" />
<limit lower="-6.2831" upper="6.2831" effort="100" velocity="6.97" />
</joint>
Expand Down
5 changes: 5 additions & 0 deletions motoman_sda10f_support/test/launch_test.xml
Original file line number Diff line number Diff line change
Expand Up @@ -38,6 +38,11 @@
<group ns="test_sda10f">
<include file="$(find motoman_sda10f_support)/launch/test_sda10f.launch"/>
</group>


<group ns="urdf_sda10f">
<param name="robot_description" command="$(find xacro)/xacro.py '$(find motoman_sda10f_support)/test/sda10f_test.xacro'" />
</group>


<group ns="robot_interface_streaming_sda10f">
Expand Down
18 changes: 18 additions & 0 deletions motoman_sda10f_support/test/sda10f_test.xacro
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
<?xml version="1.0" ?>

<robot name="motoman_sda10f_test" xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:include filename="$(find motoman_sda10f_support)/urdf/sda10f_macro.xacro" />
<xacro:motoman_sda10f prefix=""/>
<!-- xacro below should not be used, use form above-->
<!--xacro:sda10f/-->
<xacro:motoman_sda10f prefix="my_prefix_"/>


<joint name="base_link_joint" type="fixed" >
<origin xyz="1.0 0 0"/>
<parent link="torso_base_link" />
<child link="my_prefix_torso_base_link" />
</joint>

</robot>

2 changes: 1 addition & 1 deletion motoman_sda10f_support/urdf/arm_macro.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -116,7 +116,7 @@
<link name="${prefix}link_tool0" />

<joint name="${prefix}joint_1_s" type="revolute">
<parent link="torso_link_b1"/>
<parent link="${parent}"/>
<child link="${prefix}link_1_s"/>
<origin xyz="0.09996 ${reflect*0.0275} 0.32214" rpy="1.57 0 ${(reflect-1)*1.57}"/>
<axis xyz="0 0 ${-reflect}" />
Expand Down
6 changes: 3 additions & 3 deletions motoman_sda10f_support/urdf/common_torso_macro.xacro
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:macro name="torso" params="name prefix">
<!-- link list -->
<link name="base_link">
<link name="${prefix}base_link">
<visual>
<geometry>
<mesh filename="package://motoman_sda10f_support/meshes/sda10f/visual/motoman_base.stl" />
Expand Down Expand Up @@ -58,14 +58,14 @@
</link>
<!-- joint list -->
<joint name="${prefix}joint_b1" type="revolute">
<parent link="base_link"/>
<parent link="${prefix}base_link"/>
<child link="${prefix}link_b1"/>
<origin xyz="0.09257 0 0.8835" rpy="0 0 0"/>
<axis xyz="0 0 1" />
<limit lower="-2.9570" upper="2.9570" effort="100" velocity="2.26" />
</joint>
<joint name="${prefix}joint_b2" type="revolute">
<parent link="base_link"/>
<parent link="${prefix}base_link"/>
<child link="${prefix}link_b2"/>
<origin xyz="0.09257 0 0.8835" rpy="0 0 0"/>
<axis xyz="0 0 1" />
Expand Down
24 changes: 16 additions & 8 deletions motoman_sda10f_support/urdf/sda10f_macro.xacro
Original file line number Diff line number Diff line change
@@ -1,17 +1,25 @@
<?xml version="1.0" ?>
<robot xmlns:xacro="http://ros.org/wiki/xacro"
name="sda10f">
<xacro:include filename="$(find motoman_sda10f_support)/urdf/common_torso_macro.xacro" />
<xacro:include filename="$(find motoman_sda10f_support)/urdf/arm_macro.xacro" />
<robot xmlns:xacro="http://ros.org/wiki/xacro">
<xacro:include filename="$(find motoman_sda10f_support)/urdf/common_torso_macro.xacro" />
<xacro:include filename="$(find motoman_sda10f_support)/urdf/arm_macro.xacro" />
<xacro:macro name="motoman_sda10f" params="prefix">

<xacro:torso name="torso" prefix="torso_"/>
<xacro:torso name="${prefix}torso" prefix="${prefix}torso_"/>


<xacro:motoman_arm name="arm_left" prefix="arm_left_" parent="torso_link_b1" reflect="1">
<xacro:motoman_arm name="${prefix}arm_left" prefix="${prefix}arm_left_" parent="${prefix}torso_link_b1" reflect="1">
<origin xyz="0.09996 0.0275 0.32214" rpy="1.57 0 0" />
</xacro:motoman_arm>

<xacro:motoman_arm name="arm_right" prefix="arm_right_" parent="torso_link_b1" reflect="-1">
<xacro:motoman_arm name="${prefix}arm_right" prefix="${prefix}arm_right_" parent="${prefix}torso_link_b1" reflect="-1">
<origin xyz="0.09996 -0.0275 0.32214" rpy="1.57 0 0" />
</xacro:motoman_arm>
</xacro:motoman_arm>
</xacro:macro>

<!-- The following xacro is kept for backwards compatibility, it should not be used -->
<!-- see: https://github.com/ros-industrial/motoman/issues/166 -->
<xacro:macro name="sda10f">
<xacro:motoman_sda10f prefix=""/>
</xacro:macro>

</robot>

0 comments on commit a4be1a4

Please sign in to comment.