-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathmotorCommander.py
More file actions
105 lines (95 loc) · 3.68 KB
/
motorCommander.py
File metadata and controls
105 lines (95 loc) · 3.68 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
import rclpy
from rclpy.node import Node
from geometry_msgs.msg import Twist
from std_msgs.msg import Float64
import time
import warnings
warnings.filterwarnings('ignore')
class MotorController(Node):
def __init__(self):
super().__init__('motor_controller')
self.subscription = self.create_subscription(
Twist,
'/cmd_vel',
self.cmd_vel_callback,
10)
self.subscription
self.motor_publishers = [self.create_publisher(
Float64,
f'/motor_{i}/target_velocity',
10) for i in range(6)]
self.get_logger().info("MotorController node started")
self.motor_velocities = [0, 0, 0, 0, 0, 0]
def set_motor(self, motor_index, velocity):
self.motor_velocities[motor_index] = velocity
msg = Float64()
msg.data = float(velocity)
self.motor_publishers[motor_index].publish(msg)
self.get_logger().info(f"Motor {motor_index} set to {velocity}")
def cmd_vel_callback(self, msg: Twist):
linear_speed = msg.linear.x
angular_speed = msg.angular.z
print(f"linear_speed: {linear_speed}, angular_speed: {angular_speed}")
if linear_speed > 0:
self.get_logger().info("f")
self.set_motor(0, int(65535*linear_speed))
self.set_motor(1, int(65535*linear_speed))
self.set_motor(2, int(65535*linear_speed))
self.set_motor(3, int(65535*linear_speed))
self.set_motor(4, int(65535*linear_speed))
self.set_motor(5, int(65535*linear_speed))
elif linear_speed < 0:
self.get_logger().info("b")
self.set_motor(0, int(-65535*linear_speed))
self.set_motor(1, int(-65535*linear_speed))
self.set_motor(2, int(-65535*linear_speed))
self.set_motor(3, int(-65535*linear_speed))
self.set_motor(4, int(-65535*linear_speed))
self.set_motor(5, int(-65535*linear_speed))
elif angular_speed > 0:
self.get_logger().info("cw")
self.set_motor(0, int(65535*angular_speed))
self.set_motor(1, int(-65535*angular_speed))
self.set_motor(2, int(65535*angular_speed))
self.set_motor(3, int(-65535*angular_speed))
self.set_motor(4, int(65535*angular_speed))
self.set_motor(5, int(-65535*angular_speed))
elif angular_speed < 0:
self.get_logger().info("ccw")
self.set_motor(0, int(-65535*angular_speed))
self.set_motor(1, int(65535*angular_speed))
self.set_motor(2, int(-65535*angular_speed))
self.set_motor(3, int(65535*angular_speed))
self.set_motor(4, int(-65535*angular_speed))
self.set_motor(5, int(65535*angular_speed))
else:
self.get_logger().info("stop")
self.set_motor(0, 0)
self.set_motor(1, 0)
self.set_motor(2, 0)
self.set_motor(3, 0)
self.set_motor(4, 0)
self.set_motor(5, 0)
def main(args=None):
rclpy.init(args=args)
motor_controller = MotorController()
rclpy.spin(motor_controller)
motor_controller.destroy_node()
rclpy.shutdown()
if __name__ == '__main__':
main()
from launch import LaunchDescription
from launch_ros.actions import Node
def generate_launch_description():
return LaunchDescription([
Node(
package='motor_controls',
executable='motor_controller',
output='screen'
),
Node(
package='teleop_twist_keyboard',
executable='teleop_twist_keyboard',
output='screen'
)
])