aubo-old-sdk-test/node.py

180 lines
6.2 KiB
Python
Raw Normal View History

2025-05-23 18:35:17 +03:00
#!/usr/bin/env python3
import rclpy
from rclpy.node import Node
from std_msgs.msg import Float64MultiArray
2025-05-23 18:35:17 +03:00
from sensor_msgs.msg import JointState
from utils import RobotClient
import time
from main import config, HOST, PORT
2025-05-23 20:07:28 +03:00
import asyncio
2025-05-23 18:35:17 +03:00
class RobotControllerNode(Node):
def __init__(self):
super().__init__("robot_controller_node")
self.pub = self.create_publisher(
Float64MultiArray, "/forward_position_controller/commands", 10
2025-05-23 18:35:17 +03:00
)
self.js_sub = self.create_subscription(
JointState, "/joint_states", self.js_callback, 10
)
self.last_js = JointState()
self.robot_client = RobotClient(HOST, PORT)
self.get_logger().info("Robot client connected")
2025-05-23 20:19:36 +03:00
self.loop = asyncio.get_event_loop()
self.waiting_for_gripper = False
2025-05-23 18:35:17 +03:00
# Настройка скорости и ускорения
self.robot_client.set_end_max_line_velc(0.6)
self.robot_client.set_end_max_line_acc(0.8)
2025-05-23 20:19:36 +03:00
self.gripper_joint_name = "left_outer_knuckle_joint"
2025-05-23 18:35:17 +03:00
self.sequence_step = 0
# Запуск основного сценария через таймер
self.timer = self.create_timer(
1.0, self.run_sequence
) # Задержка 1 сек для инициализации
def js_callback(self, msg: JointState):
self.last_js = msg
2025-05-23 20:19:36 +03:00
async def send_gripper_command_async(
self, target_pose: float, tolerance: float = 0.01, timeout: float = 3.0
):
msg = Float64MultiArray()
2025-05-23 18:35:17 +03:00
msg.data = [target_pose]
self.pub.publish(msg)
self.get_logger().info(f"Sent gripper pose: {target_pose}")
start_time = time.time()
while rclpy.ok():
rclpy.spin_once(self, timeout_sec=0.1)
joint_name_list = list(self.last_js.name) if self.last_js.name else []
2025-05-23 20:19:36 +03:00
joint_position_list = (
list(self.last_js.position) if self.last_js.position else []
)
2025-05-23 18:35:17 +03:00
if self.gripper_joint_name in joint_name_list:
index = joint_name_list.index(self.gripper_joint_name)
if index < len(joint_position_list):
current_pose = joint_position_list[index]
if abs(current_pose - target_pose) < tolerance:
2025-05-23 20:19:36 +03:00
self.get_logger().info(
f"Gripper reached pose: {current_pose:.3f}"
)
2025-05-23 18:35:17 +03:00
return True
else:
2025-05-23 20:19:36 +03:00
self.get_logger().warn(
"Gripper joint index out of bounds in position list"
)
2025-05-23 18:35:17 +03:00
else:
2025-05-23 20:19:36 +03:00
self.get_logger().warn(
f"Gripper joint '{self.gripper_joint_name}' not found in joint_states"
)
2025-05-23 18:35:17 +03:00
return False
if time.time() - start_time > timeout:
self.get_logger().warn("Timeout waiting for gripper to reach position")
return False
2025-05-23 20:19:36 +03:00
async def handle_gripper_step(
self, target_pose: float, timeout: float = 3.0, tolerance: float = 0.01
):
try:
success = await self.send_gripper_command_async(
target_pose, tolerance, timeout
)
if success:
self.sequence_step += 1
self.get_logger().info(
f"Gripper action succeeded, moving to step {self.sequence_step}"
)
else:
self.get_logger().warn(
f"Gripper action failed or timed out at pose {target_pose}"
)
except Exception as e:
self.get_logger().error(f"Exception in handle_gripper_step: {str(e)}")
finally:
self.waiting_for_gripper = False
2025-05-23 18:35:17 +03:00
def run_sequence(self):
print(f"STEP #{self.sequence_step}")
2025-05-23 18:35:17 +03:00
if self.sequence_step == 0:
self.get_logger().info("Moving to pre-grasp")
self.robot_client.move_to_pose_joint(config["pre_grasp_position"])
self.sequence_step += 1
elif self.sequence_step == 1:
self.get_logger().info("Moving to grasp")
self.robot_client.move_to_pose_cart(config["grasp_position"])
self.sequence_step += 1
elif self.sequence_step == 2:
2025-05-23 20:19:36 +03:00
if not self.waiting_for_gripper:
self.waiting_for_gripper = True
self.loop.create_task(
self.handle_gripper_step(
target_pose=0.582, timeout=10.0, tolerance=0.1
)
)
2025-05-23 18:35:17 +03:00
elif self.sequence_step == 3:
self.get_logger().info("Moving to post-grasp")
self.robot_client.move_to_pose_cart(config["post_grasp_position"])
self.sequence_step += 1
elif self.sequence_step == 4:
self.get_logger().info("Moving to pre_insert_position")
self.robot_client.move_to_pose_cart(config["pre_insert_position"])
self.sequence_step += 1
elif self.sequence_step == 5:
self.get_logger().info("Moving to insert_position")
self.robot_client.move_to_pose_joint(config["insert_position"])
self.sequence_step += 1
elif self.sequence_step == 6:
self.get_logger().info("Moving to post_insert_position")
self.robot_client.move_to_pose_joint(config["post_insert_position"])
self.sequence_step += 1
elif self.sequence_step == 7:
2025-05-23 20:19:36 +03:00
if not self.waiting_for_gripper:
self.waiting_for_gripper = True
self.loop.create_task(
self.handle_gripper_step(target_pose=0.54, timeout=10.0)
)
2025-05-23 18:35:17 +03:00
2025-05-23 20:19:36 +03:00
elif self.sequence_step >= 8:
2025-05-23 18:35:17 +03:00
self.get_logger().info("Sequence complete")
self.robot_client.close()
self.destroy_timer(self.timer)
def main(args=None):
rclpy.init(args=args)
try:
node = RobotControllerNode()
executor = rclpy.executors.MultiThreadedExecutor()
executor.add_node(node)
try:
executor.spin()
finally:
node.destroy_node()
except Exception as e:
print(f"Fatal error: {str(e)}")
finally:
rclpy.shutdown()
if __name__ == "__main__":
main()