This repository has been archived on 2024-03-29. You can view files and clone it, but cannot push or open issues or pull requests.
rmp220_teleop_backup/rmp220_teleop/rmp220_teleop.py

77 lines
2.6 KiB
Python
Raw Normal View History

2023-04-17 08:35:47 +00:00
import rclpy
from rclpy.node import Node
from sensor_msgs.msg import Joy
from geometry_msgs.msg import Twist
2023-05-08 09:42:40 +00:00
#from segway_msgs.srv import RosSetChassisEnableCmd
2023-04-17 08:35:47 +00:00
class TeleopTwistJoy(Node):
def __init__(self):
super().__init__('teleop_twist_joy')
2023-05-08 09:42:40 +00:00
self.cmd_vel_pub = self.create_publisher(Twist, '/diffbot_base_controller/cmd_vel_unstamped', 10)
2023-04-17 08:35:47 +00:00
self.joy_sub = self.create_subscription(Joy, 'joy', self.joy_callback, 10)
2023-05-09 08:09:58 +00:00
self.timer = self.create_timer(0.1, self.timer_callback)
2023-04-17 08:35:47 +00:00
self.twist = Twist()
2023-04-18 09:34:11 +00:00
self.enable = False
2023-04-18 12:19:21 +00:00
self.limit = 0.5
2023-05-09 08:13:59 +00:00
self.max_vel = 2
2023-04-17 08:35:47 +00:00
def joy_callback(self, joy_msg):
2023-04-18 12:19:21 +00:00
if joy_msg.buttons[4]: #lb
2023-04-18 12:25:15 +00:00
self.limit -= 0.1
2023-04-18 12:19:21 +00:00
if self.limit < 0.2:
self.limit = 0.2
if joy_msg.buttons[5]: #rb
2023-04-18 12:25:15 +00:00
self.limit += 0.1
2023-05-09 08:13:59 +00:00
if self.limit > self.max_vel:
self.limit = self.max_vel
2023-04-18 12:19:21 +00:00
self.twist.linear.x = self.limit * joy_msg.axes[1]
2023-05-08 09:42:40 +00:00
self.twist.angular.z = -self.limit *2 * joy_msg.axes[0]
# if joy_msg.buttons[7]: #start
# self.enable = True
# enable_chassis(self)
# if joy_msg.buttons[6]: #back
# self.enable = False
# disable_chassis(self)
2023-04-17 08:35:47 +00:00
def timer_callback(self):
self.cmd_vel_pub.publish(self.twist)
2023-05-08 09:42:40 +00:00
# def enable_chassis(node):
# chassis_enable = node.create_client(RosSetChassisEnableCmd, '/set_chassis_enable')
# req = RosSetChassisEnableCmd.Request()
# req.ros_set_chassis_enable_cmd = True
# while not chassis_enable.wait_for_service(timeout_sec=1.0):
# print('Service not available, waiting again...')
# chassis_enable.call_async(req)
2023-04-17 08:35:47 +00:00
2023-05-08 09:42:40 +00:00
# def disable_chassis(node):
# chassis_disable = node.create_client(RosSetChassisEnableCmd, '/set_chassis_enable')
# req = RosSetChassisEnableCmd.Request()
# req.ros_set_chassis_enable_cmd = False
# while not chassis_disable.wait_for_service(timeout_sec=1.0):
# print('Service not available, waiting again...')
# chassis_disable.call_async(req)
2023-04-17 08:35:47 +00:00
def main(args=None):
rclpy.init(args=args)
try:
teleop_twist_joy = TeleopTwistJoy()
2023-05-08 09:42:40 +00:00
#enable_chassis(teleop_twist_joy) # Call the function to enable the chassis
2023-04-17 08:35:47 +00:00
rclpy.spin(teleop_twist_joy)
except KeyboardInterrupt:
2023-05-08 09:42:40 +00:00
#disable_chassis(teleop_twist_joy) # chassis disable for safe close
#req = RosSetChassisEnableCmd.Request()
#req.ros_set_chassis_enable_cmd = False
2023-04-17 08:35:47 +00:00
#rclpy.spin_until_future_complete(teleop_twist_joy, future)
teleop_twist_joy.destroy_node()
rclpy.shutdown()
2023-05-08 09:42:40 +00:00
2023-04-17 08:35:47 +00:00
if __name__ == '__main__':
main()