Skip to content

Commit

Permalink
サンプルパッケージスクリプトに英語コメントを追加 (#154)
Browse files Browse the repository at this point in the history
* Adds english comments (Still need to edit preset_pid_gain_example.py and waist_joint_trajectory_example.py)

* Adds english comments to the remaining files

* Fix typo

Co-authored-by: Shota Aoki <[email protected]>

* Fixes typo

---------

Co-authored-by: Shota Aoki <[email protected]>
  • Loading branch information
shu-13 and Shota Aoki authored Jun 18, 2024
1 parent 02182bb commit 2a3cdeb
Show file tree
Hide file tree
Showing 12 changed files with 311 additions and 54 deletions.
86 changes: 43 additions & 43 deletions sciurus17_examples/scripts/box_stacking_example.py
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ def __init__(self):

def set_angle(self, yaw_angle, pitch_angle, goal_secs=1.0e-9):
# 首を指定角度に動かす
# Move the neck to the designated angle.
# Moves the neck to the designated angle.
goal = FollowJointTrajectoryGoal()
goal.trajectory.joint_names = ["neck_yaw_joint", "neck_pitch_joint"]

Expand Down Expand Up @@ -94,7 +94,7 @@ def __init__(self):
self._gripper_goal.command.max_effort = 2.0

# アームとグリッパー姿勢の初期化
# Initialize arm and gripper pose
# Initializes arm and gripper pose
self.initialize_arms()

self._current_arm = None
Expand All @@ -108,7 +108,7 @@ def get_num_of_markers(self):

def _get_lowest_object_pose(self):
# 一番高さが低いオブジェクトのPoseを返す
# Return the Pose of the object with the lowest height.
# Returns the Pose of the object with the lowest height.

lowest_z = 1000
lowest_pose = Pose()
Expand All @@ -124,7 +124,7 @@ def _get_lowest_object_pose(self):

def _get_highest_object_pose(self):
# 一番高さが高いオブジェクトのPoseを返す
# Return the Pose of the object with the highest height
# Returns the Pose of the object with the highest height

highest_z = 0
highest_pose = Pose()
Expand All @@ -145,7 +145,7 @@ def _get_highest_object_pose(self):
def _move_arm(self, current_arm, target_pose):
if current_arm == self._RIGHT_ARM:
# 手先を下に向ける
# Pointing the hand tip downwards.
# Points the hand tip downwards.
q = quaternion_from_euler(3.14/2.0, 0.0, 0.0)
target_pose.orientation.x = q[0]
target_pose.orientation.y = q[1]
Expand All @@ -155,7 +155,7 @@ def _move_arm(self, current_arm, target_pose):
return self._right_arm.go()
elif current_arm == self._LEFT_ARM:
# 手先を下に向ける
# Pointing the hand tip downwards.
# Points the hand tip downwards.
q = quaternion_from_euler(-3.14/2.0, 0.0, 0.0)
target_pose.orientation.x = q[0]
target_pose.orientation.y = q[1]
Expand Down Expand Up @@ -211,15 +211,15 @@ def initialize_arms(self):

def pick_up(self, check_result):
# 一番高さが低いオブジェクトを持ち上げる
# Lift the object with the lowest height.
# Lifts the object with the lowest height.
rospy.loginfo("PICK UP")
result = True
# 制御対象を初期化
# Initialize control target.
self._current_arm = None

# オブジェクトがなければ終了
# Exit if no object
# Exits if no object
rospy.sleep(1.0)
if self.get_num_of_markers() == 0:
rospy.logwarn("NO OBJECTS")
Expand All @@ -228,7 +228,7 @@ def pick_up(self, check_result):
object_pose = self._get_lowest_object_pose()

# オブジェクトの位置によって左右のどちらの手で取るかを判定する
# Determine whether the object should be taken with the left or right hand depending on its position.
# Determines whether the object should be taken with the left or right hand depending on its position.
if object_pose.position.y < 0:
self._current_arm = self._RIGHT_ARM
rospy.loginfo("Set right arm")
Expand All @@ -239,20 +239,20 @@ def pick_up(self, check_result):
self._open_gripper(self._current_arm)

# Z軸方向のオフセット meters
# Offset in Z-axis (meters)
# Offset in Z-axis (meters)
APPROACH_OFFSET = 0.10
PREPARE_OFFSET = 0.06
LEAVE_OFFSET = 0.10

# 目標手先姿勢の生成
# Generate target hand pose
# Generates target hand pose
target_pose = Pose()
target_pose.position.x = object_pose.position.x
target_pose.position.y = object_pose.position.y
target_pose.position.z = object_pose.position.z

# 掴む準備をする
# Prepare to grasp
# Prepares to grasp
target_pose.position.z = object_pose.position.z + APPROACH_OFFSET
if self._move_arm(self._current_arm, target_pose) is False and check_result:
rospy.logwarn("Approach failed")
Expand All @@ -261,7 +261,7 @@ def pick_up(self, check_result):
else:
rospy.sleep(1.0)
# ハンドを下げる
# Lower the hand
# Lowers the hand
target_pose.position.z = object_pose.position.z + PREPARE_OFFSET
if self._move_arm(self._current_arm, target_pose) is False and check_result:
rospy.logwarn("Preparation grasping failed")
Expand All @@ -270,40 +270,40 @@ def pick_up(self, check_result):
else:
rospy.sleep(1.0)
# つかむ
# Grasp
# Grasps
if self._close_gripper(self._current_arm) is False and check_result:
rospy.logwarn("Grasping failed")
result = False

rospy.sleep(1.0)
# ハンドを上げる
# Raise the hand
# Raises the hand
target_pose.position.z = object_pose.position.z + LEAVE_OFFSET
self._move_arm(self._current_arm, target_pose)


if result is False:
rospy.sleep(1.0)
# 失敗したときは安全のため手を広げる
# Open the hand for safety if it fails
# Opens the hand for safety if it fails
self._open_gripper(self._current_arm)

rospy.sleep(1.0)
# 初期位置に戻る
# Return to initial position
# Returns to initial position
self._move_arm_to_init_pose(self._current_arm)

return result


def place_on(self, check_result, target_x=0.3, target_y=0):
# 座標x,yにオブジェクトを配置する
# Place the object at coordinates x,y
# Places the object at coordinates x,y
rospy.loginfo("PLACE on :" + str(target_x) + ", " + str(target_y))
result = True

# 制御アームが設定されているかチェック
# Check if the control arm is set
# Checks if the control arm is set
if self._current_arm is None:
rospy.logwarn("NO ARM SELECTED")
return False
Expand All @@ -315,22 +315,22 @@ def place_on(self, check_result, target_x=0.3, target_y=0):
LEAVE_OFFSET = 0.14

# 目標手先姿勢の生成
# Generate target hand pose
# Generates target hand pose
target_pose = Pose()
target_pose.position.x = target_x
target_pose.position.y = target_y
target_pose.position.z = 0.0

# 置く準備をする
# Prepare to place
# Prepares to place
target_pose.position.z = APPROACH_OFFSET
if self._move_arm(self._current_arm, target_pose) is False and check_result:
rospy.logwarn("Approach failed")
result = False
else:
rospy.sleep(1.0)
# ハンドを下げる
# Lower the hand
# Lowers the hand
target_pose.position.z = PREPARE_OFFSET
if self._move_arm(self._current_arm, target_pose) is False and check_result:
rospy.logwarn("Preparation release failed")
Expand All @@ -341,38 +341,38 @@ def place_on(self, check_result, target_x=0.3, target_y=0):
# Release
self._open_gripper(self._current_arm)
# ハンドを上げる
# Raise the hand
# Raises the hand
target_pose.position.z = LEAVE_OFFSET
self._move_arm(self._current_arm, target_pose)

if result is False:
rospy.sleep(1.0)
# 失敗したときは安全のため手を広げる
# Open the hand for safety if it fails to move the arm.
# Opens the hand for safety if it fails to move the arm.
self._open_gripper(self._current_arm)

rospy.sleep(1.0)
# 初期位置に戻る
# Return to initial position
# Returns to initial position
self._move_arm_to_init_pose(self._current_arm)

return result


def place_on_highest_object(self, check_result):
# 一番高さが高いオブジェクトの上に配置する
# Place on top of the highest object
# Places on top of the highest object
rospy.loginfo("PLACE ON HIGHEST OBJECT")
result = True

# 制御アームが設定されているかチェック
# Check if the control arm is set
# Checks if the control arm is set
if self._current_arm is None:
rospy.logwarn("NO ARM SELECTED")
return False

# オブジェクトが他になければデフォルト位置に置く
# Place the object in the default position if no other object exists
# Places the object in the default position if no other object exists
rospy.sleep(1.0)
if self.get_num_of_markers() == 0:
rospy.logwarn("NO OBJECTS")
Expand All @@ -387,22 +387,22 @@ def place_on_highest_object(self, check_result):
LEAVE_OFFSET = 0.15

# 目標手先姿勢の生成
# Generate target hand pose
# Generates target hand pose
target_pose = Pose()
target_pose.position.x = object_pose.position.x
target_pose.position.y = object_pose.position.y
target_pose.position.z = object_pose.position.z

# 置く準備をする
# Prepare to place
# Prepares to place
target_pose.position.z = object_pose.position.z + APPROACH_OFFSET
if self._move_arm(self._current_arm, target_pose) is False and check_result:
rospy.logwarn("Approach failed")
result = False
else:
rospy.sleep(1.0)
# ハンドを下げる
# Lower the hand
# Lowers the hand
target_pose.position.z = object_pose.position.z + PREPARE_OFFSET
if self._move_arm(self._current_arm, target_pose) is False and check_result:
rospy.logwarn("Preparation release failed")
Expand All @@ -413,30 +413,30 @@ def place_on_highest_object(self, check_result):
# Release
self._open_gripper(self._current_arm)
# ハンドを上げる
# Raise the hand
# Raises the hand
target_pose.position.z = object_pose.position.z + LEAVE_OFFSET
self._move_arm(self._current_arm, target_pose)

if result is False:
rospy.sleep(1.0)
# 失敗したときは安全のため手を広げる
# Open the hand for safety if it fails to move the arm.
# Opens the hand for safety if it fails to move the arm.
self._open_gripper(self._current_arm)

rospy.sleep(1.0)
# 初期位置に戻る
# Return to initial position
# Returns to initial position
self._move_arm_to_init_pose(self._current_arm)

return result


def hook_shutdown():
# 首の角度を戻す
# Move the neck to 0 degrees
# Moves the neck to 0 degrees
neck.set_angle(math.radians(0), math.radians(0), 3.0)
# 両腕を初期位置に戻す
# Move both arms to initial position
# Moves both arms to initial position
stacker.initialize_arms()


Expand All @@ -446,31 +446,31 @@ def main():
rospy.on_shutdown(hook_shutdown)

# 首の初期角度 degree
# Initial angle of neck. degree
# Initial angle of neck in degree
INITIAL_YAW_ANGLE = 0
INITIAL_PITCH_ANGLE = -70
# 首を下に傾けてテーブル上のものを見る
# Tilt neck down to see objects on the table
# Tilts neck down to see objects on the table
neck.set_angle(math.radians(INITIAL_YAW_ANGLE), math.radians(INITIAL_PITCH_ANGLE))

PICKING_MODE = 0
PLACE_MODE = 1
current_mode = PICKING_MODE

# 箱の配置位置 meter
# Box placement position. meter
# Box placement position in meter
PLACE_X = 0.3
PLACE_Y = 0.0

# アームとグリッパが正しく動いたかチェックする
# Check if arm and gripper moved correctly
# Checks if arm and gripper moved correctly
CHECK_RESULT = True

while not rospy.is_shutdown():
if current_mode == PICKING_MODE:
if stacker.get_num_of_markers() > 0:
# マーカがあれば、1番高さが低いオブジェクトを掴み上げる
# If there is a marker, pick up the object with the lowest height.
# If there is a marker, picks up the object with the lowest height.
if stacker.pick_up(CHECK_RESULT) is False:
rospy.logwarn("PickUp Failed")
else:
Expand All @@ -483,15 +483,15 @@ def main():
elif current_mode == PLACE_MODE:
if stacker.get_num_of_markers() == 0:
# マーカがなければ、指定位置に配置
# If there is no marker, place it at the specified position
# If there is no marker, places it at the specified position
if stacker.place_on(CHECK_RESULT, PLACE_X, PLACE_Y) is False:
rospy.logwarn("Place Failed")
else:
rospy.loginfo("Place Succeeded")

else:
# マーカがあれば、一番高い位置にあるオブジェクトの上に配置
# If there is a marker, place it on top of the highest object
# If there is a marker, places it on top of the highest object
if stacker.place_on_highest_object(CHECK_RESULT) is False:
rospy.logwarn("Place Failed")
else:
Expand Down
Loading

0 comments on commit 2a3cdeb

Please sign in to comment.