|
|
@@ -14,7 +14,16 @@ class IKCalibrationNode(IKPublisherNode): |
|
|
|
def __init__(self): |
|
|
|
super().__init__('ik_calibration') |
|
|
|
self.modified_calibration_pose = copy.deepcopy(calibration_pose) |
|
|
|
for leg in self.modified_calibration_pose['legs']: |
|
|
|
self.modified_calibration_pose['legs'][leg].z += 20 |
|
|
|
|
|
|
|
self.calibration_leg='e6' |
|
|
|
|
|
|
|
[ self.ik_values_reference ] = [ ik(calibration_pose) ] |
|
|
|
ik_values = [ ik(self.modified_calibration_pose)] |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
self.publish_ik_values(ik_values) |
|
|
|
|
|
|
|
self.cmd_vel_subscription = self.create_subscription( |
|
|
@@ -25,12 +34,22 @@ class IKCalibrationNode(IKPublisherNode): |
|
|
|
) |
|
|
|
|
|
|
|
def twist_callback(self, msg): |
|
|
|
print(msg) |
|
|
|
self.modified_calibration_pose['legs']['e1'].x -= msg.linear.x |
|
|
|
self.modified_calibration_pose['legs']['e1'].y -= msg.linear.y |
|
|
|
self.modified_calibration_pose['legs']['e1'].z -= msg.linear.z |
|
|
|
ik_values = [ ik(self.modified_calibration_pose)] |
|
|
|
self.publish_ik_values(ik_values) |
|
|
|
self.modified_calibration_pose['legs'][self.calibration_leg].x -= msg.linear.x |
|
|
|
self.modified_calibration_pose['legs'][self.calibration_leg].y -= msg.linear.y |
|
|
|
self.modified_calibration_pose['legs'][self.calibration_leg].z -= msg.linear.z |
|
|
|
ik_values_list = [ ik(self.modified_calibration_pose)] |
|
|
|
[ ik_values ] = ik_values_list |
|
|
|
|
|
|
|
im = ik_values[self.calibration_leg] |
|
|
|
ir = self.ik_values_reference[self.calibration_leg] |
|
|
|
|
|
|
|
print(im) |
|
|
|
print(ir) |
|
|
|
print([(m - r) for (m,r) in zip(im, ir)]) |
|
|
|
print([(m - r) * 129 for (m,r) in zip(im, ir)]) |
|
|
|
print() |
|
|
|
|
|
|
|
self.publish_ik_values(ik_values_list) |
|
|
|
|
|
|
|
|
|
|
|
def main(args = None): |
|
|
|