Skip to content
This repository was archived by the owner on Apr 14, 2021. It is now read-only.

Commit 35ac775

Browse files
author
Kleijwegt
committed
Updating the ROS driver basic functionality to work with the recent Python driver updates
1 parent 2977ed6 commit 35ac775

1 file changed

Lines changed: 17 additions & 17 deletions

File tree

mecademic_robot_node/src/mecademic_robot_driver/mecademic_robot_driver.py

Lines changed: 17 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -19,8 +19,8 @@ def __init__(self, robot, feedback):
1919
rospy.init_node("MecademicRobot_driver", anonymous=True)
2020
self.joint_subscriber = rospy.Subscriber("MecademicRobot_joint", JointState, self.joint_callback)
2121
self.pose_subscriber = rospy.Subscriber("MecademicRobot_pose", Pose, self.pose_callback)
22-
self.command_subcriber = rospy.Subscriber("MecademicRobot_command", String, self.command_callback)
23-
self.gripper_subcriber = rospy.Subscriber("MecademicRobot_gripper", Bool, self.gripper_callback)
22+
self.command_subscriber = rospy.Subscriber("MecademicRobot_command", String, self.command_callback)
23+
self.gripper_subscriber = rospy.Subscriber("MecademicRobot_gripper", Bool, self.gripper_callback)
2424
self.reply_publisher = rospy.Publisher("MecademicRobot_reply", String, queue_size=1)
2525
self.joint_publisher = rospy.Publisher("MecademicRobot_joint_fb", JointState, queue_size=1)
2626
self.pose_publisher = rospy.Publisher("MecademicRobot_pose_fb", Pose, queue_size=1)
@@ -41,10 +41,10 @@ def command_callback(self, command):
4141
while(not self.socket_available): #wait for socket to be available
4242
pass
4343
self.socket_available = False #block socket from being used in other processes
44-
if(self.robot.isInError()):
44+
if(self.robot.is_in_error()):
4545
self.robot.ResetError()
4646
self.robot.ResumeMotion()
47-
reply = self.robot.exchangeMsg(command.data, decode=False)
47+
reply = self.robot.exchange_msg(command.data, decode=False)
4848
self.socket_available = True #Release socket so other processes can use it
4949
if(reply is not None):
5050
self.reply_publisher.publish(reply)
@@ -60,7 +60,7 @@ def joint_callback(self, joints):
6060
pass
6161
reply = None
6262
self.socket_available = False #Block other processes from using the socket
63-
if(self.robot.isInError()):
63+
if(self.robot.is_in_error()):
6464
self.robot.ResetError()
6565
self.robot.ResumeMotion()
6666
if(len(joints.velocity)>0):
@@ -84,7 +84,7 @@ def pose_callback(self, pose):
8484
pass
8585
reply = None
8686
self.socket_available = False #Block other processes from using the socket while in use
87-
if(self.robot.isInError()):
87+
if(self.robot.is_in_error()):
8888
self.robot.ResetError()
8989
self.robot.ResumeMotion()
9090
if(pose.position.z is not None):
@@ -104,7 +104,7 @@ def gripper_callback(self, state):
104104
while(not self.socket_available): #wait for socket to be available
105105
pass
106106
self.socket_available = False #Block other processes from using the socket
107-
if(self.robot.isInError()):
107+
if(self.robot.is_in_error()):
108108
self.robot.ResetError()
109109
self.robot.ResumeMotion()
110110
if(state.data):
@@ -145,7 +145,7 @@ def feedbackLoop(self):
145145
self.status_publisher.publish(status)
146146

147147
#Position Feedback
148-
self.feedback.getData()
148+
self.feedback.get_data()
149149
joints_fb = JointState()
150150
joints_fb.position = feedback.joints
151151
pose_fb = Pose()
@@ -168,16 +168,16 @@ def __del__(self):
168168
"""Deconstructor for the Mecademic Robot ROS driver
169169
Deactivates the robot and closes socket connection with the robot
170170
"""
171-
self.robot.Deactivate()
172-
self.robot.Disconnect()
173-
self.feedback.Disconnect()
171+
self.robot.DeactivateRobot()
172+
self.robot.disconnect()
173+
self.feedback.disconnect()
174174

175175
if __name__ == "__main__":
176-
robot = RobotController('192.168.0.100')
177-
feedback = RobotFeedback('192.168.0.100')
178-
robot.Connect()
179-
feedback.Connect()
180-
robot.Activate()
181-
robot.Home()
176+
robot = RobotController('192.168.1.9')
177+
feedback = RobotFeedback('192.168.1.9', "v8.1.6.141")
178+
robot.connect()
179+
feedback.connect()
180+
robot.ActivateRobot()
181+
robot.home()
182182
driver = MecademicRobot_Driver(robot, feedback)
183183
rospy.spin()

0 commit comments

Comments
 (0)