Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
1 change: 1 addition & 0 deletions mouse_teleop/config/mouse_teleop.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -3,3 +3,4 @@ mouse_teleop:
frequency: 10.0
scale : 1.0
holonomic: False
twist_stamped: True
16 changes: 12 additions & 4 deletions mouse_teleop/mouse_teleop/mouse_teleop.py
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@
import signal
import tkinter

from geometry_msgs.msg import TwistStamped, Vector3
from geometry_msgs.msg import Twist, TwistStamped, Vector3
import numpy
import rclpy
from rclpy.node import Node
Expand All @@ -56,9 +56,15 @@ def __init__(self):
self._frequency = self.declare_parameter('frequency', 0.0).value
self._scale = self.declare_parameter('scale', 1.0).value
self._holonomic = self.declare_parameter('holonomic', False).value
self._twist_stamped = self.declare_parameter('twist_stamped', True).value

# Create twist publisher:
self._pub_cmd = self.create_publisher(TwistStamped, 'mouse_vel', 10)
if self._twist_stamped:
print("_twist_stamped true!")
self._pub_cmd = self.create_publisher(TwistStamped, 'mouse_vel', 10)
else:
print("_twist_stamped false!")
self._pub_cmd = self.create_publisher(Twist, 'mouse_vel', 10)

# Initialize twist components to zero:
self._v_x = 0.0
Expand Down Expand Up @@ -256,7 +262,10 @@ def _send_motion(self):
twist_stamped.twist.linear = lin
twist_stamped.twist.angular = ang

self._pub_cmd.publish(twist_stamped)
if self._twist_stamped:
self._pub_cmd.publish(twist_stamped)
else:
self._pub_cmd.publish(twist_stamped.twist)

def _publish_twist(self):
self._send_motion()
Expand Down Expand Up @@ -292,7 +301,6 @@ def _change_to_motion_angular(self, event):
def main():
try:
rclpy.init()

node = MouseTeleop()

node.destroy_node()
Expand Down