7 from smach
import State,StateMachine
14 from move_base_msgs.msg
import MoveBaseAction, MoveBaseGoal
18 import moveit_commander
19 import moveit_msgs.msg
20 from geometry_msgs.msg
import Pose, PoseStamped
21 import geometry_msgs.msg
23 from seed_r7_ros_controller.srv
import*
29 rospack = rospkg.RosPack()
31 path = rospack.get_path(
'seed_r7_samples')
32 with open(path +
'/config/waypoints.yaml')
as f:
36 while not self.
ac.wait_for_server(rospy.Duration(5)):
37 rospy.loginfo(
"Waiting for the move_base action server to come up")
38 rospy.loginfo(
"The server comes up");
44 rev = dict(self.
config[_number])
46 self.
goal.target_pose.header.frame_id =
'map' 47 self.
goal.target_pose.header.stamp = rospy.Time.now()
48 self.
goal.target_pose.pose.position.x = rev[
'pose'][
'position'][
'x']
49 self.
goal.target_pose.pose.position.y = rev[
'pose'][
'position'][
'y']
50 self.
goal.target_pose.pose.position.z = rev[
'pose'][
'position'][
'z']
51 self.
goal.target_pose.pose.orientation.x = rev[
'pose'][
'orientation'][
'x']
52 self.
goal.target_pose.pose.orientation.y = rev[
'pose'][
'orientation'][
'y']
53 self.
goal.target_pose.pose.orientation.z = rev[
'pose'][
'orientation'][
'z']
54 self.
goal.target_pose.pose.orientation.w = rev[
'pose'][
'orientation'][
'w']
56 rospy.loginfo(
'Sending goal')
57 self.
ac.send_goal(self.
goal)
58 succeeded = self.
ac.wait_for_result(rospy.Duration(60));
59 state = self.
ac.get_state();
61 rospy.loginfo(
"Succeed")
64 rospy.loginfo(
"Failed")
68 rospy.loginfo(
"The robot was terminated")
73 State.__init__(self, outcomes=[
'succeeded',
'aborted'])
77 rospy.loginfo(
'Going to Place'.format(self.
place_))
78 if(na.set_goal(self.
place_) ==
'succeeded'):
return 'succeeded' 79 else:
return 'aborted' 84 rospy.loginfo(
'waiting service')
85 rospy.wait_for_service(
'/seed_r7_ros_controller/hand_control')
89 service = rospy.ServiceProxy(
'/seed_r7_ros_controller/hand_control', HandControl)
90 response = service(0,
'grasp',100)
92 except rospy.ServiceException
as e:
93 rospy.logerr(
'Service call failed: {}'.format(e))
98 service = rospy.ServiceProxy(
'/seed_r7_ros_controller/hand_control', HandControl)
99 response = service(0,
'release',100)
101 except rospy.ServiceException
as e:
102 rospy.logerr(
'Service call failed: {}'.format(e))
110 self.
robot = moveit_commander.RobotCommander()
111 self.
scene = moveit_commander.PlanningSceneInterface()
113 self.
group = moveit_commander.MoveGroupCommander(
"rarm_with_torso")
114 self.
group.set_pose_reference_frame(
"base_link")
117 self.
group = moveit_commander.MoveGroupCommander(
"torso")
118 self.
group.set_pose_reference_frame(
"base_link")
119 self.
group.set_end_effector_link(
"body_link")
120 distance_body_lifter = 1.065 - 0.92
127 (position, quaternion) = listener.lookupTransform(
'base_link',
'body_link', rospy.Time(0) )
131 if(len(position)>0):
break 135 target_pose.orientation.x = 0
136 target_pose.orientation.y = 0
137 target_pose.orientation.z = 0
138 target_pose.orientation.w = 1
140 target_pose.position.x = x
141 target_pose.position.y = 0
142 target_pose.position.z = z + distance_body_lifter
144 self.
group.set_start_state_to_current_state()
145 self.
group.set_pose_target(target_pose)
146 self.
group.set_max_velocity_scaling_factor(vel)
148 if type(plan)
is tuple:
151 if(len(plan.joint_trajectory.points)==0):
152 rospy.logwarn(
"can't be solved lifter ik")
153 self.
group.clear_pose_targets()
156 self.
group.execute(plan)
160 self.
group = moveit_commander.MoveGroupCommander(
"upper_body")
161 self.
group.set_named_target(
"reset-pose")
163 if type(plan)
is tuple:
167 if(len(plan.joint_trajectory.points)==0):
168 rospy.logwarn(
"IK can't be solved")
169 self.
group.clear_pose_targets()
172 self.
group.execute(plan)
178 State.__init__(self, outcomes=[
'succeeded',
'aborted'])
184 rospy.loginfo(
'Move Lifter at ({},{}) in scale velocity {}'.format(self.
x,self.
z,self.
vel))
185 if(mc.set_lifter_position(self.
x,self.
z,self.
vel) ==
'succeeded'):
return 'succeeded' 186 else:
return 'aborted' 191 State.__init__(self, outcomes=[
'succeeded',
'aborted'])
194 rospy.loginfo(
'initialize wholebody')
196 if(mc.set_initial_pose() ==
'succeeded'):
return 'succeeded' 197 else:
return 'aborted' 202 State.__init__(self, outcomes=[
'succeeded',
'aborted'])
208 rospy.loginfo(
'FINISHED')
213 if __name__ ==
'__main__':
214 rospy.init_node(
'test_node')
220 scenario_play = StateMachine(outcomes=[
'succeeded',
'aborted'])
222 StateMachine.add(
'DOWN LIFTER',
MOVE_LIFTER(0,0.6),\
223 transitions={
'succeeded':
'FINISH',
'aborted':
'aborted'})
224 StateMachine.add(
'FINISH',
FINISH(),\
225 transitions={
'succeeded':
'succeeded',
'aborted':
'aborted'})
227 sis = smach_ros.IntrospectionServer(
'server_name',scenario_play,
'/SEED-Noid-Mover Scenario Play')
229 scenario_play.execute()
def set_goal(self, _number)
def set_lifter_position(self, x, z, vel=1.0)
def __init__(self, _place)
def execute(self, userdata)
def set_initial_pose(self)
def execute(self, userdata)
def execute(self, userdata)
遷移実行
def execute(self, userdata)
def __init__(self, x, z, vel=1.0)