Skip to content

Commit

Permalink
Fix linter errors (#54)
Browse files Browse the repository at this point in the history
* Made linter changes, uses aws_manger from common_resources

* fixed licence

* Fixed linting errors, also renamed health_report_node to not have versioning

* Fixed linting errors

* Changed circle.ci and aws.yml to lint branch

* Fixed circle ci error

* Fixed missing library

* Fixed linting errors

* Fixed linting errors

* Removed python2->python3 from future import
  • Loading branch information
BenStarmerSmith authored May 9, 2022
1 parent 4ada5e1 commit 162be1f
Show file tree
Hide file tree
Showing 22 changed files with 269 additions and 425 deletions.
2 changes: 1 addition & 1 deletion .circleci/config.yml
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@ jobs:
docker:
- image: public.ecr.aws/shadowrobot/build-tools:focal-noetic
environment:
toolset_branch: master
toolset_branch: lint
server_type: circle
ros_release_name: noetic
ubuntu_version_name: focal
Expand Down
2 changes: 1 addition & 1 deletion aws.yml
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@ settings:
tag: focal-noetic
template_project_name: template_unit_tests_and_code_coverage
toolset:
branch: master
branch: lint
modules:
- check_cache
- code_coverage
Expand Down
15 changes: 7 additions & 8 deletions sr_3dmouse/scripts/mousecontrol
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#!/usr/bin/env python 3
#!/usr/bin/env python3

# Copyright 2019 Shadow Robot Company Ltd.
# Copyright 2019, 2022 Shadow Robot Company Ltd.
#
# This program is free software: you can redistribute it and/or modify it
# under the terms of the GNU General Public License as published by the Free
Expand All @@ -15,7 +15,6 @@
# with this program. If not, see <http://www.gnu.org/licenses/>.

"3D Mouse controller"
from __future__ import absolute_import, division
from copy import deepcopy
import rospy
import tf
Expand All @@ -37,7 +36,7 @@ class MouseCommand():
"angularX": 3,
"angularY": 4,
"angularZ": 5}
self.toggleT = False
self.toggle_t = False
self.data = Joy()
self.start_pose = Pose()
# subscribe to mouse topic
Expand All @@ -58,11 +57,11 @@ class MouseCommand():
if self.data.axes:
if self.data.buttons[1]:
# toggle teach switch
self.toggleT = not self.toggleT
self._arm_commander.set_teach_mode(self.toggleT)
rospy.loginfo("Teaching toggle is:" + str(self.toggleT))
self.toggle_t = not self.toggle_t
self._arm_commander.set_teach_mode(self.toggle_t)
rospy.loginfo("Teaching toggle is:" + str(self.toggle_t))
rospy.sleep(1)
if self.toggleT is False:
if self.toggle_t is False:
self.compute_joy_pose(self.start_pose)
else:
rospy.logwarn("no data from spacenav_node. Is it running?")
Expand Down
1 change: 0 additions & 1 deletion sr_3dmouse/test/test_controller.py
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,6 @@
'''
3d mouse tester module
'''
from __future__ import absolute_import, division
import unittest
import actionlib
import rospy
Expand Down
142 changes: 70 additions & 72 deletions sr_grasp_fast_planner/src/sr_fast_grasp/fast_grasp.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#!/usr/bin/env python 3

# Copyright 2019 Shadow Robot Company Ltd.
# Copyright 2019, 2022 Shadow Robot Company Ltd.
#
# This program is free software: you can redistribute it and/or modify it
# under the terms of the GNU General Public License as published by the Free
Expand All @@ -14,71 +14,70 @@
# You should have received a copy of the GNU General Public License along
# with this program. If not, see <http://www.gnu.org/licenses/>.

from __future__ import absolute_import, division
import numpy
from copy import deepcopy

import math
import numpy
import rospy
from shape_msgs.msg import SolidPrimitive
from visualization_msgs.msg import Marker
from sr_robot_msgs.srv import GetFastGraspFromBoundingBox
from moveit_msgs.msg import Grasp
from moveit_commander import MoveGroupCommander
from moveit_msgs.msg import Grasp
from moveit_msgs.srv import GetRobotStateFromWarehouse as GetState
from moveit_msgs.srv import GetPositionIK


def quaternion_from_matrix(matrix, isprecise=False):
M = numpy.array(matrix, dtype=numpy.float64, copy=False)[:4, :4]
def quaternion_from_matrix(input_matrix, isprecise=False):
matrix = numpy.array(input_matrix, dtype=numpy.float64, copy=False)[:4, :4]
if isprecise:
q = numpy.empty((4, ))
t = numpy.trace(M)
if t > M[3, 3]:
q[0] = t
q[3] = M[1, 0] - M[0, 1]
q[2] = M[0, 2] - M[2, 0]
q[1] = M[2, 1] - M[1, 2]
quaternion = numpy.empty((4, ))
matrix_trace = numpy.trace(matrix)
if matrix_trace > matrix[3, 3]:
quaternion[0] = matrix_trace
quaternion[3] = matrix[1, 0] - matrix[0, 1]
quaternion[2] = matrix[0, 2] - matrix[2, 0]
quaternion[1] = matrix[2, 1] - matrix[1, 2]
else:
i, j, k = 1, 2, 3
if M[1, 1] > M[0, 0]:
if matrix[1, 1] > matrix[0, 0]:
i, j, k = 2, 3, 1
if M[2, 2] > M[i, i]:
if matrix[2, 2] > matrix[i, i]:
i, j, k = 3, 1, 2
t = M[i, i] - (M[j, j] + M[k, k]) + M[3, 3]
q[i] = t
q[j] = M[i, j] + M[j, i]
q[k] = M[k, i] + M[i, k]
q[3] = M[k, j] - M[j, k]
q *= 0.5 / math.sqrt(t * M[3, 3])
matrix_trace = matrix[i, i] - (matrix[j, j] + matrix[k, k]) + matrix[3, 3]
quaternion[i] = matrix_trace
quaternion[j] = matrix[i, j] + matrix[j, i]
quaternion[k] = matrix[k, i] + matrix[i, k]
quaternion[3] = matrix[k, j] - matrix[j, k]
quaternion *= 0.5 / math.sqrt(matrix_trace * matrix[3, 3])
else:
m00 = M[0, 0]
m01 = M[0, 1]
m02 = M[0, 2]
m10 = M[1, 0]
m11 = M[1, 1]
m12 = M[1, 2]
m20 = M[2, 0]
m21 = M[2, 1]
m22 = M[2, 2]
# symmetric matrix K
K = numpy.array([[m00-m11-m22, 0.0, 0.0, 0.0],
[m01+m10, m11-m00-m22, 0.0, 0.0],
[m02+m20, m12+m21, m22-m00-m11, 0.0],
[m21-m12, m02-m20, m10-m01, m00+m11+m22]])
K /= 3.0
# quaternion is eigenvector of K that corresponds to largest eigenvalue
w, V = numpy.linalg.eigh(K)
q = V[[3, 0, 1, 2], numpy.argmax(w)]
if q[0] < 0.0:
numpy.negative(q, q)
return q
m00 = matrix[0, 0]
m01 = matrix[0, 1]
m02 = matrix[0, 2]
m10 = matrix[1, 0]
m11 = matrix[1, 1]
m12 = matrix[1, 2]
m20 = matrix[2, 0]
m21 = matrix[2, 1]
m22 = matrix[2, 2]
# symmetric matrix
sym_matrix = numpy.array([[m00-m11-m22, 0.0, 0.0, 0.0],
[m01+m10, m11-m00-m22, 0.0, 0.0],
[m02+m20, m12+m21, m22-m00-m11, 0.0],
[m21-m12, m02-m20, m10-m01, m00+m11+m22]])
sym_matrix /= 3.0
# quaternion is eigenvector of sym_matrix that corresponds to largest eigenvalue
eigh_val, eigh_matrix = numpy.linalg.eigh(sym_matrix)
quaternion = eigh_matrix[[3, 0, 1, 2], numpy.argmax(eigh_val)]
if quaternion[0] < 0.0:
numpy.negative(quaternion, quaternion)
return quaternion


class SrFastGrasp:
def __init__(self):
self.__marker_pub = rospy.Publisher("visualization_marker",
Marker, queue_size=1)
self.__grasp_server = rospy.Service("grasp_from_bounding_box",
self.__grasp_server = rospy.Service("grasp_from_bounding_box", # pylint: disable=W0238
GetFastGraspFromBoundingBox,
self.__bounding_box_cb)
self.__default_grasp = 'super_amazing_grasp'
Expand All @@ -89,43 +88,42 @@ def __init__(self):
arm_group = rospy.get_param("~arm_group", "right_arm")

self.__group = MoveGroupCommander(hand_group)
self.__arm_g = MoveGroupCommander(arm_group)
self.__ik = rospy.ServiceProxy("compute_ik", GetPositionIK)
self.__arm_g = MoveGroupCommander(arm_group) # pylint: disable=W0238
self.__ik = rospy.ServiceProxy("compute_ik", GetPositionIK) # pylint: disable=W0238

def __modify_grasp_pose(self, grasp, pose):
# pylint: disable=R0201
"""
Aligns grasp with axis from origin to center of object.
A crude way to make a vaguely sane orientation for the hand
that seems to more or less work.
"""

v1 = numpy.array([pose.pose.position.x,
pose.pose.position.y,
pose.pose.position.z])
v1_length = numpy.linalg.norm(v1)
val1 = numpy.array([pose.pose.position.x,
pose.pose.position.y,
pose.pose.position.z])
val1_length = numpy.linalg.norm(val1)

v1 = v1/v1_length
val1 = val1/val1_length

v2 = [1, 0, -v1[0]/v1[2]]
v2 = v2/numpy.linalg.norm(v2)
val2 = [1, 0, -val1[0]/val1[2]]
val2 = val2/numpy.linalg.norm(val2)

v3 = numpy.cross(v1, v2)
v3 = v3/numpy.linalg.norm(v3)
val3 = numpy.cross(val1, val2)
val3 = val3/numpy.linalg.norm(val3)

m = [
[v3[0], v1[0], v2[0]],
[v3[1], v1[1], v2[1]],
[v3[2], v1[2], v2[2]]
matrix = [
[val3[0], val1[0], val2[0]],
[val3[1], val1[1], val2[1]],
[val3[2], val1[2], val2[2]]
]

q = quaternion_from_matrix(m)

quaternion = quaternion_from_matrix(matrix)
grasp.grasp_pose = deepcopy(pose)

grasp.grasp_pose.pose.orientation.x = q[0]
grasp.grasp_pose.pose.orientation.y = q[1]
grasp.grasp_pose.pose.orientation.z = q[2]
grasp.grasp_pose.pose.orientation.w = q[3]
grasp.grasp_pose.pose.orientation.x = quaternion[0]
grasp.grasp_pose.pose.orientation.y = quaternion[1]
grasp.grasp_pose.pose.orientation.z = quaternion[2]
grasp.grasp_pose.pose.orientation.w = quaternion[3]

def __bounding_box_cb(self, request):
box = request.bounding_box
Expand Down Expand Up @@ -174,16 +172,16 @@ def __get_grasp(self, name):

return grasp

def __get_major_axis(self, box):
m = max(box.dimensions)
max_index = [i for i, j in enumerate(box.dimensions) if j == m]
def __get_major_axis(self, box): # pylint: disable=W0238,R0201
max_box = max(box.dimensions)
max_index = [i for i, j in enumerate(box.dimensions) if j == max_box]
return max_index[-1] # Get the LAST axis with max val.

def __send_marker_to_rviz(self, box, pose):
marker = self.__get_marker_from_box(box, pose)
self.__marker_pub.publish(marker)

def __get_marker_from_box(self, box, pose):
def __get_marker_from_box(self, box, pose): # pylint: disable=R0201
marker = Marker()
marker.pose = pose.pose
marker.header.frame_id = pose.header.frame_id
Expand All @@ -204,7 +202,7 @@ def __get_marker_from_box(self, box, pose):
return marker


if "__main__" == __name__:
if __name__ == "__main__":
rospy.init_node('sr_fast_grasp')
grasp = SrFastGrasp()
grasp_class = SrFastGrasp()
rospy.spin()
27 changes: 13 additions & 14 deletions sr_grasp_fast_planner/src/sr_fast_grasp/grasp_saver.py
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
#!/usr/bin/env python 3

# Copyright 2019 Shadow Robot Company Ltd.
# Copyright 2019, 2022 Shadow Robot Company Ltd.
#
# This program is free software: you can redistribute it and/or modify it
# under the terms of the GNU General Public License as published by the Free
Expand All @@ -14,33 +14,32 @@
# You should have received a copy of the GNU General Public License along
# with this program. If not, see <http://www.gnu.org/licenses/>.

from __future__ import absolute_import
from sys import argv
import sys
import rospy
from moveit_msgs.srv import SaveRobotStateToWarehouse as SaveState
from sensor_msgs.msg import JointState
from moveit_msgs.msg import RobotState
from sensor_msgs.msg import JointState


class GraspSaver:
def __init__(self, name):
self.__group_name = "right_hand"
self.__group_name = "right_hand" # pylint: disable=W0238
self.__save = rospy.ServiceProxy(
'/moveit_warehouse_services/save_robot_state', SaveState)
self.__js_subscriber = rospy.Subscriber("joint_states",
self.__js_subscriber = rospy.Subscriber("joint_states", # pylint: disable=W0238
JointState,
self.__js_cb)
self.__js = None
self.__done = False
self.__name = name

def __js_cb(self, js):
def __js_cb(self, js): # pylint: disable=C0103
self.__js = js

def __save_out(self):
rs = RobotState()
rs.joint_state = self.__js
self.__save(self.__name, "", rs)
robotstate = RobotState()
robotstate.joint_state = self.__js
self.__save(self.__name, "", robotstate)

def spin(self):
while not self.__done and not rospy.is_shutdown():
Expand All @@ -51,10 +50,10 @@ def spin(self):
rospy.sleep(.1)


if "__main__" == __name__:
if __name__ == "__main__":
rospy.init_node("grasp_saver")
if len(argv) <= 1 or "" == argv[1]:
if len(sys.argv) <= 1 or sys.argv[1] == "":
rospy.logerr("You didn't enter a name.")
exit(-1)
gs = GraspSaver(argv[1])
sys.exit(-1)
gs = GraspSaver(sys.argv[1])
gs.spin()
Loading

0 comments on commit 162be1f

Please sign in to comment.