Skip to content

Commit

Permalink
[FEAT] Add new env. var. to control speed
Browse files Browse the repository at this point in the history
The env. var. is set in .env file and the format is like
WHEEL_SPEED=3
  • Loading branch information
otischung committed Nov 27, 2023
1 parent 85543af commit 42f0b71
Show file tree
Hide file tree
Showing 7 changed files with 59 additions and 44 deletions.
2 changes: 1 addition & 1 deletion car_control.sh
Original file line number Diff line number Diff line change
@@ -1 +1 @@
docker run -it --rm --device=/dev/usb_front_wheel --device=/dev/usb_rear_wheel --network host ghcr.io/otischung/pros_car:latest /bin/bash
docker run -it --rm --device=/dev/usb_front_wheel --device=/dev/usb_rear_wheel --network host --env-file ./.env ghcr.io/otischung/pros_car:latest /bin/bash
15 changes: 5 additions & 10 deletions docker-compose.yml
Original file line number Diff line number Diff line change
Expand Up @@ -7,11 +7,11 @@ services:
tty: false
env_file:
- .env
environment:
- ROS_DOMAIN_ID
- SERIAL_DEV_DEFAULT
- SERIAL_FRONT_DEFAULT
- SERIAL_LIDAR_DEFAULT
# environment:
# - ROS_DOMAIN_ID
# - SERIAL_DEV_DEFAULT
# - SERIAL_FRONT_DEFAULT
# - SERIAL_LIDAR_DEFAULT
networks:
- my_bridge_network
# privileged: true
Expand All @@ -27,11 +27,6 @@ services:
tty: true # docker run -t
env_file:
- .env
environment:
- ROS_DOMAIN_ID
- SERIAL_DEV_DEFAULT
- SERIAL_FRONT_DEFAULT
- SERIAL_LIDAR_DEFAULT
networks:
- my_bridge_network
# privileged: true
Expand Down
20 changes: 12 additions & 8 deletions src/pros_car_py/pros_car_py/carA_keyboard.py
Original file line number Diff line number Diff line change
Expand Up @@ -9,11 +9,13 @@
import threading
from sensor_msgs.msg import JointState
from trajectory_msgs.msg import JointTrajectoryPoint
from pros_car_py.env import *


class CarAKeyboardController(Node):
def __init__(self, stdscr):
def __init__(self, stdscr, vel: float = 10):
super().__init__('car_A_keyboard')
self.vel = vel

# Subscriber
self.subscription = self.create_subscription(
Expand Down Expand Up @@ -65,8 +67,9 @@ def _pub_control(self):

self.get_logger().info(f'publish {control_msg}')

def run(self):

def run(self, vel=None):
if vel is None:
vel = self.vel
self.stdscr.nodelay(True)
try:
while rclpy.ok():
Expand All @@ -77,13 +80,13 @@ def run(self):
self.key_in_count += 1
self.print_basic_info(c)
if c == ord('w'):
self.handle_key_w()
self.handle_key_w(vel)
elif c == ord('a'):
self.handle_key_a()
self.handle_key_a(vel)
elif c == ord('s'):
self.handle_key_s()
self.handle_key_s(vel)
elif c == ord('d'):
self.handle_key_d()
self.handle_key_d(vel)
elif c == ord('z'):
self.handle_key_z()
elif c == ord('i'):
Expand Down Expand Up @@ -226,7 +229,8 @@ def pub_arm(self):
def main(args=None):
rclpy.init(args=args)
stdscr = curses.initscr()
node = CarAKeyboardController(stdscr)
vel = 10 if WHEEL_SPEED is None else float(WHEEL_SPEED)
node = CarAKeyboardController(stdscr, vel=vel)

# Spin the node in a separate thread
spin_thread = threading.Thread(target=rclpy.spin, args=(node,), daemon=True)
Expand Down
19 changes: 12 additions & 7 deletions src/pros_car_py/pros_car_py/carB_keyboard.py
Original file line number Diff line number Diff line change
Expand Up @@ -9,11 +9,13 @@
import threading
from sensor_msgs.msg import JointState
from trajectory_msgs.msg import JointTrajectoryPoint
from pros_car_py.env import *


class CarBKeyboardController(Node):
def __init__(self, stdscr):
def __init__(self, stdscr, vel: float = 10):
super().__init__('car_B_keyboard')
self.vel = vel

# Subscriber
self.subscription = self.create_subscription(
Expand Down Expand Up @@ -64,7 +66,9 @@ def _pub_control(self):

self.get_logger().info(f'publish {control_msg}')

def run(self):
def run(self, vel=None):
if vel is None:
vel = self.vel
self.stdscr.nodelay(True)
try:
while rclpy.ok():
Expand All @@ -75,13 +79,13 @@ def run(self):
self.key_in_count += 1
self.print_basic_info(c)
if c == ord('w'):
self.handle_key_w()
self.handle_key_w(vel)
elif c == ord('a'):
self.handle_key_a()
self.handle_key_a(vel)
elif c == ord('s'):
self.handle_key_s()
self.handle_key_s(vel)
elif c == ord('d'):
self.handle_key_d()
self.handle_key_d(vel)
elif c == ord('z'):
self.handle_key_z()
elif c == ord('q'): # Exit on 'q'
Expand Down Expand Up @@ -164,7 +168,8 @@ def handle_key_z(self):
def main(args=None):
rclpy.init(args=args)
stdscr = curses.initscr()
node = CarBKeyboardController(stdscr)
vel = 10 if WHEEL_SPEED is None else float(WHEEL_SPEED)
node = CarBKeyboardController(stdscr, vel=vel)

# Spin the node in a separate thread
spin_thread = threading.Thread(target=rclpy.spin, args=(node,), daemon=True)
Expand Down
23 changes: 14 additions & 9 deletions src/pros_car_py/pros_car_py/carC_keyboard.py
Original file line number Diff line number Diff line change
Expand Up @@ -9,11 +9,13 @@
import threading
from sensor_msgs.msg import JointState
from trajectory_msgs.msg import JointTrajectoryPoint
from pros_car_py.env import *


class CarCKeyboardController(Node):
def __init__(self, stdscr):
def __init__(self, stdscr, vel: float = 10):
super().__init__('car_C_keyboard')
self.vel = vel

# Subscriber
self.subscription = self.create_subscription(
Expand Down Expand Up @@ -83,7 +85,9 @@ def _pub_control(self):
self.get_logger().info(f'publish {control_msg}')
self.get_logger().info(f'publish to forward {control_msg_forward}')

def run(self):
def run(self, vel=None):
if vel is None:
vel = self.vel
self.stdscr.nodelay(True)
try:
while rclpy.ok():
Expand All @@ -94,17 +98,17 @@ def run(self):
self.key_in_count += 1
self.print_basic_info(c)
if c == ord('w'):
self.handle_key_w()
self.handle_key_w(vel)
elif c == ord('a'):
self.handle_key_a()
self.handle_key_a(vel)
elif c == ord('s'):
self.handle_key_s()
self.handle_key_s(vel)
elif c == ord('d'):
self.handle_key_d()
self.handle_key_d(vel)
elif c == ord('e'):
self.handle_key_e()
self.handle_key_e(vel)
elif c == ord('r'):
self.handle_key_r()
self.handle_key_r(vel)
elif c == ord('z'):
self.handle_key_z()
elif c == ord('q'): # Exit on 'q'
Expand Down Expand Up @@ -213,7 +217,8 @@ def handle_key_z(self):
def main(args=None):
rclpy.init(args=args)
stdscr = curses.initscr()
node = CarCKeyboardController(stdscr)
vel = 10 if WHEEL_SPEED is None else float(WHEEL_SPEED)
node = CarCKeyboardController(stdscr, vel=vel)

# Spin the node in a separate thread
spin_thread = threading.Thread(target=rclpy.spin, args=(node,), daemon=True)
Expand Down
23 changes: 14 additions & 9 deletions src/pros_car_py/pros_car_py/carD_keyboard.py
Original file line number Diff line number Diff line change
Expand Up @@ -9,11 +9,13 @@
import threading
from sensor_msgs.msg import JointState
from trajectory_msgs.msg import JointTrajectoryPoint
from pros_car_py.env import *


class CarDKeyboardController(Node):
def __init__(self, stdscr):
def __init__(self, stdscr, vel: float = 10):
super().__init__('car_D_keyboard')
self.vel = vel

# Subscriber
self.subscription = self.create_subscription(
Expand Down Expand Up @@ -83,7 +85,9 @@ def _pub_control(self):
self.get_logger().info(f'publish {control_msg}')
self.get_logger().info(f'publish to forward {control_msg_forward}')

def run(self):
def run(self, vel=None):
if vel is None:
vel = self.vel
self.stdscr.nodelay(True)
try:
while rclpy.ok():
Expand All @@ -94,17 +98,17 @@ def run(self):
self.key_in_count += 1
self.print_basic_info(c)
if c == ord('w'):
self.handle_key_w()
self.handle_key_w(vel)
elif c == ord('a'):
self.handle_key_a()
self.handle_key_a(vel)
elif c == ord('s'):
self.handle_key_s()
self.handle_key_s(vel)
elif c == ord('d'):
self.handle_key_d()
self.handle_key_d(vel)
elif c == ord('e'):
self.handle_key_e()
self.handle_key_e(vel)
elif c == ord('r'):
self.handle_key_r()
self.handle_key_r(vel)
elif c == ord('z'):
self.handle_key_z()
elif c == ord('q'): # Exit on 'q'
Expand Down Expand Up @@ -213,7 +217,8 @@ def handle_key_z(self):
def main(args=None):
rclpy.init(args=args)
stdscr = curses.initscr()
node = CarDKeyboardController(stdscr)
vel = 10 if WHEEL_SPEED is None else float(WHEEL_SPEED)
node = CarDKeyboardController(stdscr, vel=vel)

# Spin the node in a separate thread
spin_thread = threading.Thread(target=rclpy.spin, args=(node,), daemon=True)
Expand Down
1 change: 1 addition & 0 deletions src/pros_car_py/pros_car_py/env.py
Original file line number Diff line number Diff line change
Expand Up @@ -2,5 +2,6 @@

SERIAL_DEV_DEFAULT = os.getenv('SERIAL_DEV_DEFAULT', '/dev/usb_rear_wheel') # replace with your default value
SERIAL_DEV_FORWARD_DEFAULT = os.getenv('SERIAL_DEV_FORWARD_DEFAULT', '/dev/usb_front_wheel') # replace with your default value
WHEEL_SPEED = os.getenv('WHEEL_SPEED')
# SERIAL_BACK_DEFAULT = os.getenv('SERIAL_BACK_DEFAULT', '/dev/ttyUSB0') # replace with your default value
# SERIAL_FRONT_DEFAULT = os.getenv('SERIAL_FRONT_DEFAULT', '/dev/ttyUSB1') # replace with your default value

0 comments on commit 42f0b71

Please sign in to comment.