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

Feature: Custom python functions for dependent joints #64

Open
wants to merge 2 commits into
base: noetic-devel
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
50 changes: 29 additions & 21 deletions joint_state_publisher/src/joint_state_publisher/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -248,32 +248,15 @@ def loop(self):
# Add Free Joint
if name in self.free_joints:
joint = self.free_joints[name]
factor = 1
offset = 0

# Add Dependent Joint
elif name in self.dependent_joints:
param = self.dependent_joints[name]
parent = param['parent']
factor = param.get('factor', 1)
offset = param.get('offset', 0)
# Handle recursive mimic chain
recursive_mimic_chain_joints = [name]
while parent in self.dependent_joints:
if parent in recursive_mimic_chain_joints:
error_message = "Found an infinite recursive mimic chain"
rospy.logerr("%s: [%s, %s]", error_message, ', '.join(recursive_mimic_chain_joints), parent)
sys.exit(1)
recursive_mimic_chain_joints.append(parent)
param = self.dependent_joints[parent]
parent = param['parent']
offset += factor * param.get('offset', 0)
factor *= param.get('factor', 1)
joint = self.free_joints[parent]
joint = self.compute_dependent_joint(name, [])

if has_position and 'position' in joint:
msg.position[i] = joint['position'] * factor + offset
msg.position[i] = joint['position']
if has_velocity and 'velocity' in joint:
msg.velocity[i] = joint['velocity'] * factor
msg.velocity[i] = joint['velocity']
if has_effort and 'effort' in joint:
msg.effort[i] = joint['effort']

Expand All @@ -284,6 +267,31 @@ def loop(self):
r.sleep()
except rospy.exceptions.ROSTimeMovedBackwardsException:
pass

def compute_dependent_joint(self, name, recursive_mimic_chain_joints):
param = self.dependent_joints[name]
parent = param['parent']
loc = param.copy()
loc['factor'] = param.get('factor', 1) #to allow default behaviour
loc['offset'] = param.get('offset', 0)
dependent_fun = param.get('fun', "position = parent_position * factor + offset")
#Handle recursive mimic chain
recursive_mimic_chain_joints.append(name)
if (parent in self.dependent_joints):
if parent in recursive_mimic_chain_joints:
error_message = "Found an infinite recursive mimic chain"
rospy.logerr("%s: [%s, %s]", error_message, ', '.join(recursive_mimic_chain_joints), parent)
sys.exit(1)
loc['parent_position'] = self.compute_dependent_joint(parent, recursive_mimic_chain_joints)['position']
else:
loc['parent_position'] = self.free_joints[parent]['position']

exec(dependent_fun, globals(), loc)
ret = {}
ret['position'] = loc['position']
#TODO: velocity
return ret


def update(self, delta):
for name, joint in self.free_joints.iteritems():
Expand Down
57 changes: 57 additions & 0 deletions joint_state_publisher/test/nonlinear_dependent_chain.urdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,57 @@
<?xml version="1.0"?>
<robot name="nonlinear_dependent_chain">
<link name="finger1">
<visual>
<origin xyz="0.0628 -0.0207 0.0" rpy="0 0 -0.2584" />
<geometry>
<box size="0.149 0.0277 0.07" />
</geometry>
</visual>
</link>
<link name="finger2">
<visual>
<origin xyz="0.0628 0.0207 0.0" rpy="0 0 0.2584" />
<geometry>
<box size="0.149 0.0277 0.07" />
</geometry>
</visual>
</link>
<link name="base">
<visual>
<origin xyz="0 0 0" rpy="0 0 0" />
<geometry>
<box size="0.2 0.2 0.001" />
</geometry>
</visual>
</link>

<link name="piston">
<visual>
<origin xyz="0 0 -0.1" rpy="0 0 0" />
<geometry>
<box size="0.02 0.02 0.2" />
</geometry>
</visual>
</link>

<joint name="finger1_joint" type="revolute">
<origin rpy="0 -1.57 0" xyz="0 -0.033 0" />
<parent link="base" />
<child link="finger1" />
<axis xyz="0 0 -1" />
<limit effort="10" velocity="10" lower="-1" upper="1" />
</joint>
<joint name="finger2_joint" type="revolute">
<origin rpy="0 -1.57 0" xyz="0 0.033 0" />
<parent link="base" />
<child link="finger2" />
<axis xyz="0 0 -1" />
<limit effort="10" velocity="10" lower="-1" upper="1" />
</joint>
<joint name="piston_joint" type="prismatic">
<parent link="base" />
<child link="piston" />
<axis xyz="0 0 1"/>
<limit effort="10" velocity="10" lower="-0.02" upper="0.04" />
</joint>
</robot>
33 changes: 33 additions & 0 deletions joint_state_publisher/test/test_nonlinear_dependent_chain.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,33 @@
<?xml version="1.0"?>
<launch>
<param name="robot_description" textfile="$(find joint_state_publisher)/test/nonlinear_dependent_chain.urdf"/>

<rosparam>
dependent_joints:
finger1_joint: {
parent: piston_joint,
p_off: -0.004,
z1: 0.03636756796927724,
z2: 0.025,
q_off: -0.820403314,
fun: "j = parent_position + p_off\nposition = (-2.0 * math.atan2((z1 - math.sqrt(math.pow(z1, 2) + math.pow(z2, 2) - math.pow(j, 2))), (z2 - j))) + q_off"
}
finger2_joint: {
parent: finger1_joint,
fun: "position = -1 * parent_position"
}
</rosparam>

<node pkg="joint_state_publisher_gui" type="joint_state_publisher_gui" name="dut_joint_state_publisher_gui">
<param name="rate" value="10"/>
</node>

<node name="robot_state_publisher" pkg="robot_state_publisher" type="robot_state_publisher" output="screen"/>
<test pkg="rostest" type="hztest" name="hztest" test-name="hztest_mimic_chain">
<param name="topic" value="joint_states"/>
<param name="hz" value="10"/>
<param name="hzerror" value="0.1"/>
<param name="test_duration" value="10"/>
<param name="wait_time" value="10"/>
</test>
</launch>