update twist

This commit is contained in:
Your Name 2023-06-15 14:59:54 +02:00
parent 5d0513a073
commit b70b7124ed
5 changed files with 27 additions and 18 deletions

2
.gitignore vendored
View File

@ -2,3 +2,5 @@ install/
log/
build/
.vscode/
*__pycache__*

5
README.md Normal file
View File

@ -0,0 +1,5 @@
# DCAITI_WS
## Jetson IP Adresses
Onboard switch: 192.168.1.253
TIB switch: 192.168.13.142

View File

@ -14,16 +14,16 @@
<!-- Note everything below here is the same as the Gazebo one -->
<joint name="left_wheel_joint">
<command_interface name="velocity">
<param name="min">-0.5</param>
<param name="max">0.5</param>
<param name="min">-0.005</param>
<param name="max">0.005</param>
</command_interface>
<state_interface name="velocity"/>
<state_interface name="position"/>
</joint>
<joint name="right_wheel_joint">
<command_interface name="velocity">
<param name="min">-0.5</param>
<param name="max">0.5</param>
<param name="min">-0.005</param>
<param name="max">0.005</param>
</command_interface>
<state_interface name="velocity"/>
<state_interface name="position"/>

View File

@ -7,10 +7,14 @@ from sensor_msgs.msg import Joy
import numpy as np
SCALE_LINEAR_VELOCITY = 0.5
SCALE_ANGULAR_VELOCITY = 0.4
PUBLISH_FREQUENCY_HZ = 10
def calc_speed_from_joy(x, y):
linear = -y
angular = -x
linear = -y * SCALE_LINEAR_VELOCITY
angular = x * SCALE_ANGULAR_VELOCITY
return linear, angular
@ -18,19 +22,22 @@ class TwistPublisher(Node):
def __init__(self):
super().__init__('twist_publisher')
self.publisher_ = self.create_publisher(Twist, 'cmd_vel', 1)
self.linear = 0.0
self.angular = 0.0
self.publisher_ = self.create_publisher(Twist, '/diff_cont/cmd_vel_unstamped', 1)
self.create_subscription(Joy, "/joy", self.joy_callback, 1)
self.timer = self.create_timer(1/PUBLISH_FREQUENCY_HZ, self.timer_callback)
def joy_callback(self, joy_message):
x, y = joy_message.axes[:2]
linear, angular = calc_speed_from_joy(x,y)
self.linear, self.angular = calc_speed_from_joy(x,y)
def timer_callback(self):
msg = Twist()
msg.linear.x = linear
msg.angular.z = angular
msg.linear.x = self.linear
msg.angular.z = self.angular
self.publisher_.publish(msg)
self.get_logger().info('Publishing: "%s"' % msg)

View File

@ -12,10 +12,5 @@ def generate_launch_description():
package='dcaitirobot',
executable='twistcalc',
name='twistcalc',
),
Node(
package='dcaitirobot',
executable='serial_comms',
name='serial',
)
])