00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 import copy
00036 import math
00037
00038 import actionlib
00039 from moveit_commander import MoveGroupCommander
00040 from moveit_commander import MoveItCommanderException
00041 import rospy
00042 from pr2_controllers_msgs.msg import JointTrajectoryAction
00043 from pr2_controllers_msgs.msg import JointTrajectoryGoal
00044 from trajectory_msgs.msg import JointTrajectoryPoint
00045 from tf.transformations import quaternion_from_euler
00046
00047 from hironx_ros_bridge.constant import Constant
00048
00049 _MSG_ASK_ISSUEREPORT = 'Your report to ' + \
00050 'https://github.com/start-jsk/rtmros_hironx/issues ' + \
00051 'about the issue you are seeing is appreciated.'
00052
00053
00054 class ROS_Client(object):
00055 '''
00056 This class:
00057
00058 - holds methods that are specific to Kawada Industries' dual-arm
00059 robot called Hiro, via ROS.
00060 - As of July 2014, this class is only intended to be used through HIRONX
00061 class.
00062 '''
00063
00064 _MSG_NO_MOVEGROUP_FOUND = ('\nMake sure you\'ve launched MoveGroup ' +
00065 '(e.g. by launching ' +
00066 'moveit_planning_execution.launch)')
00067
00068 def __init__(self, jointgroups=None):
00069 '''
00070 @type jointgroups: [str]
00071 '''
00072
00073 try:
00074 rospy.get_master().getSystemState()
00075 except Exception:
00076 print('[ros_client] ros master is not running, so do not create ros client...')
00077 return
00078
00079 rospy.init_node('hironx_ros_client')
00080 if jointgroups:
00081 self._set_groupnames(jointgroups)
00082
00083 if not rospy.has_param('robot_description'):
00084 rospy.logwarn('ROS Bridge is not started yet, Assuming you want just to use RTM')
00085 return
00086
00087 self._init_action_clients()
00088
00089 if not rospy.has_param('robot_description_semantic'):
00090 rospy.logwarn('Moveit is not started yet, if you want to use MoveIt!' + self._MSG_NO_MOVEGROUP_FOUND)
00091 return
00092 self._movegr_larm = self._movegr_rarm = None
00093 try:
00094 self._init_moveit_commanders()
00095 except RuntimeError as e:
00096 rospy.logerr(str(e) + self._MSG_NO_MOVEGROUP_FOUND)
00097
00098 def _init_moveit_commanders(self):
00099 '''
00100 @raise RuntimeError: When MoveGroup is not running.
00101 '''
00102
00103
00104 try:
00105 self._movegr_larm = MoveGroupCommander(Constant.GRNAME_LEFT_ARM_MOVEGROUP)
00106 self._movegr_rarm = MoveGroupCommander(Constant.GRNAME_RIGHT_ARM_MOVEGROUP)
00107 except RuntimeError as e:
00108 raise e
00109
00110 def _init_action_clients(self):
00111 self._aclient_larm = actionlib.SimpleActionClient(
00112 '/larm_controller/joint_trajectory_action', JointTrajectoryAction)
00113 self._aclient_rarm = actionlib.SimpleActionClient(
00114 '/rarm_controller/joint_trajectory_action', JointTrajectoryAction)
00115 self._aclient_head = actionlib.SimpleActionClient(
00116 '/head_controller/joint_trajectory_action', JointTrajectoryAction)
00117 self._aclient_torso = actionlib.SimpleActionClient(
00118 '/torso_controller/joint_trajectory_action', JointTrajectoryAction)
00119
00120 self._aclient_larm.wait_for_server()
00121 self._goal_larm = JointTrajectoryGoal()
00122 self._goal_larm.trajectory.joint_names.append("LARM_JOINT0")
00123 self._goal_larm.trajectory.joint_names.append("LARM_JOINT1")
00124 self._goal_larm.trajectory.joint_names.append("LARM_JOINT2")
00125 self._goal_larm.trajectory.joint_names.append("LARM_JOINT3")
00126 self._goal_larm.trajectory.joint_names.append("LARM_JOINT4")
00127 self._goal_larm.trajectory.joint_names.append("LARM_JOINT5")
00128
00129 self._aclient_rarm.wait_for_server()
00130 self._goal_rarm = JointTrajectoryGoal()
00131 self._goal_rarm.trajectory.joint_names.append("RARM_JOINT0")
00132 self._goal_rarm.trajectory.joint_names.append("RARM_JOINT1")
00133 self._goal_rarm.trajectory.joint_names.append("RARM_JOINT2")
00134 self._goal_rarm.trajectory.joint_names.append("RARM_JOINT3")
00135 self._goal_rarm.trajectory.joint_names.append("RARM_JOINT4")
00136 self._goal_rarm.trajectory.joint_names.append("RARM_JOINT5")
00137
00138 self._aclient_head.wait_for_server()
00139 self._goal_head = JointTrajectoryGoal()
00140 self._goal_head.trajectory.joint_names.append('HEAD_JOINT0')
00141 self._goal_head.trajectory.joint_names.append('HEAD_JOINT1')
00142
00143 self._aclient_torso.wait_for_server()
00144 self._goal_torso = JointTrajectoryGoal()
00145 self._goal_torso.trajectory.joint_names.append('CHEST_JOINT0')
00146
00147 rospy.loginfo('Joint names; ' +
00148 'Torso: {}\n\tHead: {}\n\tL-Arm: {}\n\tR-Arm: {}'.format(
00149 self._goal_torso.trajectory.joint_names,
00150 self._goal_head.trajectory.joint_names,
00151 self._goal_larm.trajectory.joint_names,
00152 self._goal_rarm.trajectory.joint_names))
00153
00154 def _set_groupnames(self, groupnames):
00155 '''
00156 @type groupnames: [str]
00157 @param groupnames: List of the joint group names. Assumes to be in the
00158 following order:
00159 torso, head, right arm, left arm.
00160 This current setting is derived from the order of
00161 Groups argument in HIRONX class. If other groups
00162 need to be defined in the future, this method may
00163 need to be modified.
00164 '''
00165 rospy.loginfo('_set_groupnames; groupnames={}'.format(groupnames))
00166 self._GR_TORSO = groupnames[0]
00167 self._GR_HEAD = groupnames[1]
00168 self._GR_RARM = groupnames[2]
00169 self._GR_LARM = groupnames[3]
00170
00171 def go_init(self, task_duration=7.0):
00172 '''
00173 Init positions are taken from HIRONX.
00174 TODO: Need to add factory position too that's so convenient when
00175 working with the manufacturer.
00176 @type task_duration: float
00177 '''
00178 rospy.loginfo('*** go_init begins ***')
00179 POSITIONS_TORSO_DEG = [0.0]
00180 self.set_joint_angles_deg(Constant.GRNAME_TORSO, POSITIONS_TORSO_DEG, task_duration)
00181 POSITIONS_HEAD_DEG = [0.0, 0.0]
00182 self.set_joint_angles_deg(Constant.GRNAME_HEAD, POSITIONS_HEAD_DEG, task_duration)
00183 POSITIONS_LARM_DEG = [0.6, 0, -100, -15.2, 9.4, -3.2]
00184 self.set_joint_angles_deg(Constant.GRNAME_LEFT_ARM, POSITIONS_LARM_DEG, task_duration)
00185 POSITIONS_RARM_DEG = [-0.6, 0, -100, 15.2, 9.4, 3.2]
00186 self.set_joint_angles_deg(Constant.GRNAME_RIGHT_ARM, POSITIONS_RARM_DEG,
00187 task_duration, wait=True)
00188 rospy.loginfo(self._goal_larm.trajectory.points)
00189
00190 def set_joint_angles_rad(self, groupname, positions_radian, duration=7.0,
00191 wait=False):
00192 '''
00193 @type groupname: str
00194 @param groupname: This should exist in self.groupnames.
00195 @type positions_radian: [float]
00196 @type duration: float
00197 @type wait: bool
00198 '''
00199 if groupname == Constant.GRNAME_TORSO:
00200 action_client = self._aclient_torso
00201 goal = self._goal_torso
00202 elif groupname == Constant.GRNAME_HEAD:
00203 action_client = self._aclient_head
00204 goal = self._goal_head
00205 elif groupname == Constant.GRNAME_LEFT_ARM:
00206 action_client = self._aclient_larm
00207 goal = self._goal_larm
00208 elif groupname == Constant.GRNAME_RIGHT_ARM:
00209 action_client = self._aclient_rarm
00210 goal = self._goal_rarm
00211 else:
00212
00213 rospy.logerr('groupname {} not assigned'.format(groupname))
00214
00215 try:
00216 pt = JointTrajectoryPoint()
00217 pt.positions = positions_radian
00218 pt.time_from_start = rospy.Duration(duration)
00219 goal.trajectory.points = [pt]
00220 goal.trajectory.header.stamp = \
00221 rospy.Time.now() + rospy.Duration(duration)
00222
00223 action_client.send_goal(goal)
00224 if wait:
00225 rospy.loginfo(
00226 'wait_for_result for the joint group {} = {}'.format(
00227 groupname, action_client.wait_for_result()))
00228 except rospy.ROSInterruptException as e:
00229 rospy.loginfo(e.str())
00230
00231 def set_joint_angles_deg(self, groupname, positions_deg, duration=7.0,
00232 wait=False):
00233 '''
00234 @type groupname: str
00235 @param groupname: This should exist in self.groupnames.
00236 @type positions_deg: [float]
00237 @type duration: float
00238 @type wait: bool
00239 '''
00240 self.set_joint_angles_rad(groupname, self._to_rad_list(positions_deg),
00241 duration, wait)
00242
00243 def _to_rad_list(self, list_degree):
00244 '''
00245 @TODO Needs to be replaced by something more common, or at least moved
00246 somewhere more common.
00247
00248 @type list_degree: [float]
00249 @param list_degree: A list length of the number of joints.
00250 '''
00251 list_rad = []
00252 for deg in list_degree:
00253 rad = math.radians(deg)
00254 list_rad.append(rad)
00255 rospy.logdebug('Position deg={} rad={}'.format(deg, rad))
00256 return list_rad
00257
00258 def set_pose(self, joint_group, position, rpy=None, task_duration=7.0,
00259 do_wait=True, ref_frame_name=None):
00260 '''
00261 Accept pose defined by position and RPY in Cartesian format.
00262
00263 @type joint_group: str
00264 @type position: [float]
00265 @param position: x, y, z.
00266 @type rpy: [float]
00267 @param rpy: If None, keep the current orientation by using
00268 MoveGroupCommander.set_position_target. See:
00269 'http://moveit.ros.org/doxygen/' +
00270 'classmoveit__commander_1_1move__group_1_1' +
00271 'MoveGroupCommander.html#acfe2220fd85eeb0a971c51353e437753'
00272 @param ref_frame_name: TODO: Not utilized yet. Need to be implemented.
00273 '''
00274
00275 if not self._movegr_larm or not self._movegr_rarm:
00276 try:
00277 self._init_moveit_commanders()
00278 except RuntimeError as e:
00279 rospy.logerr(self._MSG_NO_MOVEGROUP_FOUND)
00280 raise e
00281
00282
00283 movegr = None
00284 if Constant.GRNAME_LEFT_ARM == joint_group:
00285 movegr = self._movegr_larm
00286 elif Constant.GRNAME_RIGHT_ARM == joint_group:
00287 movegr = self._movegr_rarm
00288 else:
00289 rospy.loginfo('444')
00290
00291
00292 if not rpy:
00293 try:
00294 movegr.set_position_target(position)
00295 except MoveItCommanderException as e:
00296 rospy.logerr(str(e))
00297 return
00298
00299
00300
00301 pose = copy.deepcopy(position)
00302 pose.extend(rpy)
00303 rospy.loginfo('setpose jntgr={} mvgr={} pose={} posi={} rpy={}'.format(
00304 joint_group, movegr, pose, position, rpy))
00305 try:
00306 movegr.set_pose_target(pose)
00307 except MoveItCommanderException as e:
00308 rospy.logerr(str(e))
00309 except Exception as e:
00310 rospy.logerr(str(e))
00311
00312 (movegr.go(do_wait) or movegr.go(do_wait) or
00313 rospy.logerr('MoveGroup.go fails; jointgr={}'.format(joint_group)))