Skip to content

Commit

Permalink
finalizing PR
Browse files Browse the repository at this point in the history
  • Loading branch information
fmessmer committed Apr 5, 2017
1 parent d296d14 commit 6d6ca8f
Show file tree
Hide file tree
Showing 3 changed files with 44 additions and 38 deletions.
74 changes: 37 additions & 37 deletions cob_bringup/drivers/ur.launch
Original file line number Diff line number Diff line change
@@ -1,43 +1,43 @@
<?xml version="1.0"?>
<launch>

<arg name="robot" default="$(optenv ROBOT !!NO_ROBOT_SET!!)"/>
<arg name="component_name" default="arm"/>
<arg name="use_modern_driver" default="false"/>
<arg name="robot_ip" default="localhost"/>
<arg name="reverse_port" default="50001"/>
<arg name="min_payload" default="0.0"/>
<arg name="max_payload" default="10.0"/>
<arg name="prefix" default="arm_"/>
<arg name="sim" default="false"/>
<arg name="cartesian_control" default="false"/>
<arg name="robot" default="$(optenv ROBOT !!NO_ROBOT_SET!!)"/>
<arg name="component_name" default="arm"/>
<arg name="use_modern_driver" default="false"/>
<arg name="robot_ip" default="localhost"/>
<arg name="reverse_port" default="50001"/>
<arg name="min_payload" default="0.0"/>
<arg name="max_payload" default="10.0"/>
<arg name="prefix" default="arm_"/>
<arg name="sim" default="false"/>
<arg name="cartesian_control" default="false"/>

<group unless="$(arg sim)">
<!-- universal robot arm -->
<node unless="$(arg use_modern_driver)" ns="arm/joint_trajectory_controller" pkg="ur_driver" type="driver.py" name="ur_driver" args="$(arg robot_ip) $(arg reverse_port)" output="screen">
<remap from="/arm/joint_trajectory_controller/joint_states" to="/arm/joint_states"/>
<remap from="/arm/joint_trajectory_controller/robot_description" to="/robot_description"/>
<param name="min_payload" type="double" value="$(arg min_payload)"/>
<param name="max_payload" type="double" value="$(arg max_payload)"/>
<param name="prefix" value="$(arg prefix)"/>
</node>
<!-- universal robot arm modern driver -->
<!--node if="$(arg use_modern_driver)" ns="arm/joint_trajectory_controller" pkg="ur_modern_driver" type="ur_driver" name="ur_driver" args="$(arg robot_ip) $(arg reverse_port)" output="screen">
<remap from="/arm/joint_trajectory_controller/joint_states" to="/arm/joint_states"/>
<remap from="/arm/joint_trajectory_controller/robot_description" to="/robot_description"/>
<param name="min_payload" type="double" value="$(arg min_payload)"/>
<param name="max_payload" type="double" value="$(arg max_payload)"/>
<param name="prefix" value="$(arg prefix)"/>
</node-->
</group>
<include if="$(arg sim)" file="$(find cob_bringup)/controllers/generic_controller.launch">
<arg name="robot" value="$(arg robot)"/>
<arg name="component_name" value="$(arg component_name)"/>
</include>
<include if="$(arg cartesian_control)" file="$(find cob_bringup)/controllers/generic_cartesian_controller.launch">
<arg name="robot" value="$(arg robot)"/>
<arg name="component_name" value="$(arg component_name)"/>
<arg name="debug" value="false"/>
</include>
<group unless="$(arg sim)">
<!-- universal robot python driver -->
<node unless="$(arg use_modern_driver)" ns="arm/joint_trajectory_controller" pkg="ur_driver" type="driver.py" name="ur_driver" args="$(arg robot_ip) $(arg reverse_port)" output="screen">
<remap from="/arm/joint_trajectory_controller/joint_states" to="/arm/joint_states"/>
<remap from="/arm/joint_trajectory_controller/robot_description" to="/robot_description"/>
<param name="min_payload" type="double" value="$(arg min_payload)"/>
<param name="max_payload" type="double" value="$(arg max_payload)"/>
<param name="prefix" value="$(arg prefix)"/>
</node>
<!-- universal robot modern driver -->
<!--node if="$(arg use_modern_driver)" ns="arm/joint_trajectory_controller" pkg="ur_modern_driver" type="ur_driver" name="ur_driver" args="$(arg robot_ip) $(arg reverse_port)" output="screen">
<remap from="/arm/joint_trajectory_controller/joint_states" to="/arm/joint_states"/>
<remap from="/arm/joint_trajectory_controller/robot_description" to="/robot_description"/>
<param name="min_payload" type="double" value="$(arg min_payload)"/>
<param name="max_payload" type="double" value="$(arg max_payload)"/>
<param name="prefix" value="$(arg prefix)"/>
</node-->
</group>
<include if="$(arg sim)" file="$(find cob_bringup)/controllers/generic_controller.launch">
<arg name="robot" value="$(arg robot)"/>
<arg name="component_name" value="$(arg component_name)"/>
</include>
<include if="$(arg cartesian_control)" file="$(find cob_bringup)/controllers/generic_cartesian_controller.launch">
<arg name="robot" value="$(arg robot)"/>
<arg name="component_name" value="$(arg component_name)"/>
<arg name="debug" value="false"/>
</include>

</launch>
Original file line number Diff line number Diff line change
Expand Up @@ -41,11 +41,12 @@ twist_controller:
keep_direction: true
enforce_input_limits: true
enforce_pos_limits: true
enforce_pos_limits: true
enforce_vel_limits: true
enforce_acc_limits: false
limits_tolerance: 5.0 #for position limits [deg]
#limits_acc: [10.0, 10.0, 10.0, 10.0, 10.0, 10.0, 10.0] #[rad/s2]
max_lin_twist: 0.5
max_rot_twist: 0.5

# kinematic extensions
kinematic_extension: 0 #OFF 0, BaseCompensation 1, BaseActive 2
Expand Down
5 changes: 5 additions & 0 deletions cob_moveit_config/raw3-1/config/raw3-1.srdf
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,9 @@
<group name="arm">
<chain base_link="arm_base_link" tip_link="arm_ee_link" />
</group>
<group name="endeffector">
<link name="arm_ee_link"/>
</group>
<group name="robot">
<joint name="base" />
<joint name="arm_shoulder_pan_joint" />
Expand All @@ -21,6 +24,8 @@
<joint name="arm_wrist_2_joint" />
<joint name="arm_wrist_3_joint" />
</group>
<!--END EFFECTOR: Purpose: Represent information about an end effector.-->
<end_effector name="moveit_ee" parent_link="arm_ee_link" group="endeffector" />
<!--VIRTUAL JOINT: Purpose: this element defines a virtual joint between a robot link and an external frame of reference (considered fixed with respect to the robot)-->
<virtual_joint name="base" type="planar" parent_frame="odom_combined" child_link="base_footprint" />
<!--DISABLE COLLISIONS: By default it is assumed that any link of the robot could potentially come into collision with any other link in the robot. This tag disables collision checking between a specified pair of links. -->
Expand Down

0 comments on commit 6d6ca8f

Please sign in to comment.