joint_force_viz.py
Go to the documentation of this file.
00001 #! /usr/bin/python
00002 
00003 import sys
00004 import numpy as np
00005 
00006 import roslib
00007 roslib.load_manifest("hrl_pr2_arms")
00008 roslib.load_manifest("kelsey_sandbox")
00009 import rospy
00010 from visualization_msgs.msg import Marker
00011 from geometry_msgs.msg import Point, Quaternion, Vector3
00012 from std_msgs.msg import ColorRGBA
00013 from sensor_msgs.msg import JointState
00014 
00015 import urdf_interface as urdf
00016 import kdl_parser as kdlp
00017 from hrl_pr2_arms.kdl_arm_kinematics import KDLArmKinematics
00018 
00019 JOINT_STATE_INDS_R = [17, 18, 16, 20, 19, 21, 22]
00020 JOINT_STATE_INDS_L = [29, 30, 28, 32, 31, 33, 34]
00021 
00022 class JointForceViz:
00023     def __init__(self, arm):
00024         self.arm = arm
00025         self.vis_pub = rospy.Publisher("force_torque_markers", Marker)
00026         if arm == 'r':
00027             self.arm_inds = JOINT_STATE_INDS_R
00028         else:
00029             self.arm_inds = JOINT_STATE_INDS_L
00030         model = urdf.create_model_from_file("/etc/ros/diamondback/urdf/robot.xml")
00031         tree = kdlp.tree_from_urdf_model(model)
00032         chain = tree.getChain("torso_lift_link", "r_gripper_tool_frame")
00033         link_dict = {0:0, 1:1, 2:2, 3:3, 4:4, 5:5, 6:6, 7:11}
00034         self.kinematics = KDLArmKinematics(chain=chain, link_dict=link_dict)
00035         self.colors = [ColorRGBA(1., 0., 0., 1.), ColorRGBA(0., 1., 0., 1.)]
00036         rospy.Subscriber("joint_states", JointState, self.joint_states_cb)
00037 
00038     def joint_states_cb(self, msg):
00039         q_pos = np.mat([msg.position[i] for i in self.arm_inds]).T
00040         q_vel = np.mat([msg.velocity[i] for i in self.arm_inds]).T
00041         q_effort = np.mat([msg.effort[i] for i in self.arm_inds]).T
00042         fk_pos, fk_rot = self.kinematics.FK(q_pos)
00043         J = self.kinematics.jacobian(q_pos)
00044         F, res, rank, sing = np.linalg.lstsq(J.T, q_effort)
00045         #print "Force:", F[0:3]
00046         #print "Torque:", F[3:6]
00047         self.publish_vector(fk_pos, 0.01 * F[0:3], 0)
00048         self.publish_vector(fk_pos, 0.04 * F[3:6], 1)
00049 
00050     def publish_vector(self, loc, v, m_id):
00051         m = Marker()
00052         m.header.frame_id = "torso_lift_link"
00053         m.header.stamp = rospy.Time()
00054         m.ns = "force_torque"
00055         m.id = m_id
00056         m.type = Marker.ARROW
00057         m.action = Marker.ADD
00058         m.points.append(Point(*loc))
00059         m.points.append(Point(*(loc + v)))
00060         m.scale = Vector3(0.01, 0.02, 0.01)
00061         m.color = self.colors[m_id]
00062         self.vis_pub.publish(m)
00063 
00064 
00065 def main():
00066     assert sys.argv[1] in ['r', 'l']
00067     rospy.init_node("test_markers")
00068 
00069     jfv = JointForceViz(sys.argv[1])
00070     rospy.spin()
00071     return
00072 
00073 if __name__ == "__main__":
00074     main()


kelsey_sandbox
Author(s): kelsey
autogenerated on Wed Nov 27 2013 11:52:04