Skip to content

Commit 3936f23

Browse files
committed
solve merge conflict
2 parents 52e0b9a + bd9f2a1 commit 3936f23

File tree

3 files changed

+30
-2
lines changed

3 files changed

+30
-2
lines changed

launch/camera_calibration.launch

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,6 @@
11
<launch>
22
<include file="position_control.launch"/>
3+
<include file="$(find openface2_ros)/launch/openface2_ros.launch"/>
34
<include file="$(find realsense2_camera)/launch/rs_camera.launch">
45
<arg name="enable_pointcloud" value="true"/>
56
</include>

scripts/controller.py

Lines changed: 17 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,7 @@
11
import numpy as np
22
import rospy
3+
import time
4+
from collections import deque
35

46
from std_msgs.msg import Float64, Empty
57
from trac_ik_python.trac_ik import IK
@@ -18,6 +20,8 @@ def __init__(self):
1820
rospy.Subscriber('/joint_states', JointState, self.get_joint_state)
1921
self.tf_listener = tf.TransformListener()
2022

23+
self.history = {'timestamp': deque(),
24+
'joint_feedback': deque()}
2125
# global variables
2226
self.current_joint_state = None
2327
self.current_gripper_state = None
@@ -59,6 +63,19 @@ def set_arm_joint_angles(self, joint_target):
5963
rospy.sleep(4)
6064

6165
def get_joint_state(self, data):
66+
# TODO: Change this when required
67+
moveable_joints = [1,2,3]
68+
# Add timestamp
69+
self.history['timestamp'].append(time.time())
70+
if(len(self.history['timestamp']) > 20):
71+
self.history['timestamp'].popleft()
72+
73+
# Add Joint Feedback
74+
joint_angles = np.array(data.position)[moveable_joints]
75+
self.history['joint_feedback'].append(joint_angles)
76+
if(len(self.history['joint_feedback']) > 20):
77+
self.history['joint_feedback'].popleft()
78+
6279
self.current_joint_state = data.position[0:5]
6380
self.current_gripper_state = data.position[7:9]
6481

scripts/machine.py

Lines changed: 12 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -4,6 +4,7 @@
44
import rospy
55
import smach
66
import smach_ros
7+
import numpy as np
78

89
from controller import Controller
910
from geometry_msgs.msg import PoseStamped
@@ -12,6 +13,7 @@
1213

1314
# Initialize controller
1415
ctrl = Controller()
16+
MIN_JOINT_MOTION_FOR_HAND_OVER = 0.1
1517
# define state Idle
1618
class Idle(smach.State):
1719
def __init__(self):
@@ -168,9 +170,17 @@ def __init__(self):
168170

169171
def execute(self, userdata):
170172
## Detect when to Open gripper
171-
ctrl.open_gripper()
172173
rospy.loginfo('Executing state OpenGripper')
173-
return 'opened'
174+
while(True):
175+
joint_len = len(ctrl.history['joint_feedback'][0])
176+
joint_sum = np.zeros(ctrl.history['joint_feedback'][0].shape)
177+
for joint_feedback in ctrl.history['joint_feedback']:
178+
joint_sum += joint_feedback
179+
avg_joint_sum = joint_sum/joint_len
180+
if(np.sum(avg_joint_sum) < MIN_JOINT_MOTION_FOR_HAND_OVER):
181+
ctrl.open_gripper()
182+
return 'opened'
183+
174184

175185
def main():
176186
rospy.init_node('attention_bot')

0 commit comments

Comments
 (0)