From 0e4f874b9ef6f8e7c844bd7c834e16def089fa72 Mon Sep 17 00:00:00 2001 From: Kleijwegt Date: Fri, 9 Apr 2021 11:18:00 +0200 Subject: [PATCH] Updating the ROS driver basic functionality to work with the recent Python driver updates --- .../mecademic_robot_driver.py | 32 +++++++++---------- 1 file changed, 16 insertions(+), 16 deletions(-) diff --git a/mecademic_robot_node/src/mecademic_robot_driver/mecademic_robot_driver.py b/mecademic_robot_node/src/mecademic_robot_driver/mecademic_robot_driver.py index d69b5f4..40a456a 100755 --- a/mecademic_robot_node/src/mecademic_robot_driver/mecademic_robot_driver.py +++ b/mecademic_robot_node/src/mecademic_robot_driver/mecademic_robot_driver.py @@ -19,8 +19,8 @@ def __init__(self, robot, feedback): rospy.init_node("MecademicRobot_driver", anonymous=True) self.joint_subscriber = rospy.Subscriber("MecademicRobot_joint", JointState, self.joint_callback) self.pose_subscriber = rospy.Subscriber("MecademicRobot_pose", Pose, self.pose_callback) - self.command_subcriber = rospy.Subscriber("MecademicRobot_command", String, self.command_callback) - self.gripper_subcriber = rospy.Subscriber("MecademicRobot_gripper", Bool, self.gripper_callback) + self.command_subscriber = rospy.Subscriber("MecademicRobot_command", String, self.command_callback) + self.gripper_subscriber = rospy.Subscriber("MecademicRobot_gripper", Bool, self.gripper_callback) self.reply_publisher = rospy.Publisher("MecademicRobot_reply", String, queue_size=1) self.joint_publisher = rospy.Publisher("MecademicRobot_joint_fb", JointState, queue_size=1) self.pose_publisher = rospy.Publisher("MecademicRobot_pose_fb", Pose, queue_size=1) @@ -41,10 +41,10 @@ def command_callback(self, command): while(not self.socket_available): #wait for socket to be available pass self.socket_available = False #block socket from being used in other processes - if(self.robot.isInError()): + if(self.robot.is_in_error()): self.robot.ResetError() self.robot.ResumeMotion() - reply = self.robot.exchangeMsg(command.data, decode=False) + reply = self.robot.exchange_msg(command.data, decode=False) self.socket_available = True #Release socket so other processes can use it if(reply is not None): self.reply_publisher.publish(reply) @@ -60,7 +60,7 @@ def joint_callback(self, joints): pass reply = None self.socket_available = False #Block other processes from using the socket - if(self.robot.isInError()): + if(self.robot.is_in_error()): self.robot.ResetError() self.robot.ResumeMotion() if(len(joints.velocity)>0): @@ -84,7 +84,7 @@ def pose_callback(self, pose): pass reply = None self.socket_available = False #Block other processes from using the socket while in use - if(self.robot.isInError()): + if(self.robot.is_in_error()): self.robot.ResetError() self.robot.ResumeMotion() if(pose.position.z is not None): @@ -104,7 +104,7 @@ def gripper_callback(self, state): while(not self.socket_available): #wait for socket to be available pass self.socket_available = False #Block other processes from using the socket - if(self.robot.isInError()): + if(self.robot.is_in_error()): self.robot.ResetError() self.robot.ResumeMotion() if(state.data): @@ -145,7 +145,7 @@ def feedbackLoop(self): self.status_publisher.publish(status) #Position Feedback - self.feedback.getData() + self.feedback.get_data() joints_fb = JointState() joints_fb.position = feedback.joints pose_fb = Pose() @@ -168,16 +168,16 @@ def __del__(self): """Deconstructor for the Mecademic Robot ROS driver Deactivates the robot and closes socket connection with the robot """ - self.robot.Deactivate() - self.robot.Disconnect() - self.feedback.Disconnect() + self.robot.DeactivateRobot() + self.robot.disconnect() + self.feedback.disconnect() if __name__ == "__main__": robot = RobotController('192.168.0.100') - feedback = RobotFeedback('192.168.0.100') - robot.Connect() - feedback.Connect() - robot.Activate() - robot.Home() + feedback = RobotFeedback('192.168.0.100', "v8.1.6.141") + robot.connect() + feedback.connect() + robot.ActivateRobot() + robot.home() driver = MecademicRobot_Driver(robot, feedback) rospy.spin() \ No newline at end of file