Added Config.py
This commit is contained in:
@@ -16,6 +16,14 @@ from geometry_msgs.msg import Twist, Point
|
||||
from std_msgs.msg import String
|
||||
import json
|
||||
|
||||
# Load configuration
|
||||
try:
|
||||
from config import ROVER
|
||||
CONFIG_LOADED = True
|
||||
except ImportError:
|
||||
CONFIG_LOADED = False
|
||||
ROVER = {"default_pattern": "stationary", "default_speed": 0.5, "default_amplitude": 2.0}
|
||||
|
||||
|
||||
class MovementPattern(Enum):
|
||||
STATIONARY = "stationary"
|
||||
@@ -28,21 +36,22 @@ class MovementPattern(Enum):
|
||||
class RoverController(Node):
|
||||
"""Controls the rover movement."""
|
||||
|
||||
DEFAULT_PATTERN = MovementPattern.STATIONARY
|
||||
DEFAULT_SPEED = 0.5
|
||||
DEFAULT_AMPLITUDE = 2.0
|
||||
CONTROL_RATE = 50.0
|
||||
MAX_X = 5.0
|
||||
MAX_Y = 5.0
|
||||
|
||||
def __init__(
|
||||
self,
|
||||
pattern: MovementPattern = DEFAULT_PATTERN,
|
||||
speed: float = DEFAULT_SPEED,
|
||||
amplitude: float = DEFAULT_AMPLITUDE
|
||||
pattern: MovementPattern = None,
|
||||
speed: float = None,
|
||||
amplitude: float = None
|
||||
):
|
||||
super().__init__('rover_controller')
|
||||
|
||||
# Use config defaults if not specified
|
||||
if pattern is None:
|
||||
pattern = MovementPattern(ROVER.get("default_pattern", "stationary"))
|
||||
if speed is None:
|
||||
speed = ROVER.get("default_speed", 0.5)
|
||||
if amplitude is None:
|
||||
amplitude = ROVER.get("default_amplitude", 2.0)
|
||||
|
||||
self._pattern = pattern
|
||||
self._speed = speed
|
||||
self._amplitude = amplitude
|
||||
@@ -55,6 +64,9 @@ class RoverController(Node):
|
||||
self._target_y = 0.0
|
||||
self._random_timer = 0.0
|
||||
self._square_segment = 0
|
||||
self._control_rate = 50.0
|
||||
self._max_x = 5.0
|
||||
self._max_y = 5.0
|
||||
|
||||
self.get_logger().info('=' * 50)
|
||||
self.get_logger().info('Rover Controller Starting...')
|
||||
@@ -69,21 +81,21 @@ class RoverController(Node):
|
||||
|
||||
self.get_logger().info(' Publishing to: /rover/cmd_vel, /rover/position, /rover/telemetry')
|
||||
|
||||
control_period = 1.0 / self.CONTROL_RATE
|
||||
control_period = 1.0 / self._control_rate
|
||||
self._control_timer = self.create_timer(control_period, self._control_loop)
|
||||
|
||||
self.get_logger().info('Rover Controller Ready!')
|
||||
|
||||
def _control_loop(self) -> None:
|
||||
dt = 1.0 / self.CONTROL_RATE
|
||||
dt = 1.0 / self._control_rate
|
||||
self._time += dt
|
||||
|
||||
vel_x, vel_y = self._calculate_velocity()
|
||||
|
||||
self._position.x += vel_x * dt
|
||||
self._position.y += vel_y * dt
|
||||
self._position.x = max(-self.MAX_X, min(self.MAX_X, self._position.x))
|
||||
self._position.y = max(-self.MAX_Y, min(self.MAX_Y, self._position.y))
|
||||
self._position.x = max(-self._max_x, min(self._max_x, self._position.x))
|
||||
self._position.y = max(-self._max_y, min(self._max_y, self._position.y))
|
||||
|
||||
cmd = Twist()
|
||||
cmd.linear.x = vel_x
|
||||
@@ -148,7 +160,7 @@ class RoverController(Node):
|
||||
return (vel_x, vel_y)
|
||||
|
||||
def _pattern_random(self) -> Tuple[float, float]:
|
||||
dt = 1.0 / self.CONTROL_RATE
|
||||
dt = 1.0 / self._control_rate
|
||||
self._random_timer += dt
|
||||
if self._random_timer >= 3.0:
|
||||
self._random_timer = 0.0
|
||||
|
||||
Reference in New Issue
Block a user