hardware
Bms ¶
Bms(**kwargs)
Bases: Module
, ABC
The BMS module communicates with a simple battery management system over a serial connection.
The BMS module provides measured voltages as an event.
is_above_percent ¶
is_above_percent(value: float) -> bool
Returns whether the battery is charged above the given percentage.
is_above_voltage ¶
is_above_voltage(value: float) -> bool
Returns whether the battery voltage is above the given value.
is_below_percent ¶
is_below_percent(value: float) -> bool
Returns whether the battery is charged below the given percentage.
is_below_voltage ¶
is_below_voltage(value: float) -> bool
Returns whether the battery voltage is below the given value.
BmsHardware ¶
BmsHardware(
robot_brain: RobotBrain,
*,
expander: ExpanderHardware | None = None,
name: str = "bms",
rx_pin: int = 26,
tx_pin: int = 27,
baud: int = 9600,
num: int = 1,
charge_detect_threshold: float = -0.4
)
BmsSimulation ¶
BmsSimulation(
is_charging: Callable[[], bool] | None = None,
fixed_voltage: float | None = None,
)
Bumper ¶
Bumper(estop: EStop | None, **kwargs)
Bases: Module
, ABC
A module that detects when a bumper is triggered.
Events¶
Name | Description |
---|---|
BUMPER_TRIGGERED | a bumper was triggered (argument: the bumper name) |
BumperHardware ¶
BumperHardware(
robot_brain: RobotBrain,
*,
expander: ExpanderHardware | None = None,
name: str = "bumper",
pins: dict[str, int],
estop: EStop | None = None
)
Bases: Bumper
, ModuleHardware
Hardware implementation of the bumper module.
The module expects a dictionary of pin names and pin numbers. If an e-stop is provided, the module will not trigger bumpers if the e-stop is active.
Events¶
Name | Description |
---|---|
BUMPER_TRIGGERED | a bumper was triggered (argument: the bumper name) |
BumperSimulation ¶
BumperSimulation(estop: EStop | None, **kwargs)
Events¶
Name | Description |
---|---|
BUMPER_TRIGGERED | a bumper was triggered (argument: the bumper name) |
Communication ¶
Communication()
Bases: ABC
This abstract module defines an interface for communicating with a microcontroller.
Besides sending and receiving messages a communication module provides a property whether communication is possible. It can also provide a piece of debug UI.
EStop ¶
EStop(**kwargs)
Bases: Module
, ABC
A module that detects when the e-stop is triggered.
The module has a boolean field active
that is true when the e-stop is triggered.
There is also a boolean field is_soft_estop_active
that is true when the soft e-stop is active.
It can be set to true or false by calling set_soft_estop(active: bool)
.
Events¶
Name | Description |
---|---|
ESTOP_TRIGGERED | the e-stop was triggered |
EStopHardware ¶
EStopHardware(
robot_brain: RobotBrain,
*,
name: str = "estop",
pins: dict[str, int]
)
Bases: EStop
, ModuleHardware
Hardware implementation of the e-stop module.
The module expects a dictionary of pin names and pin numbers.
Events¶
Name | Description |
---|---|
ESTOP_TRIGGERED | the e-stop was triggered |
EStopSimulation ¶
EStopSimulation(**kwargs)
Events¶
Name | Description |
---|---|
ESTOP_TRIGGERED | the e-stop was triggered |
ExpanderHardware ¶
ExpanderHardware(
robot_brain: RobotBrain,
*,
name: str = "p0",
serial: SerialHardware,
boot: int = 25,
enable: int = 14
)
Bases: ModuleHardware
The expander module represents a second ESP microcontroller connected to the core ESP via serial.
Events¶
Name | Description |
---|---|
NEW_MEASUREMENT | a new measurement has been received (argument: GnssMeasurement ) |
GnssHardware ¶
GnssHardware(*, antenna_pose: Pose | None)
Bases: Gnss
This hardware module connects to a Septentrio SimpleRTK3b (Mosaic-H) GNSS receiver.
:param antenna_pose: the pose of the main antenna in the robot's coordinate frame (yaw: direction to the auxiliary antenna)
_antenna_angle
instance-attribute
¶
_antenna_angle = pi + atan2(y, x) - yaw
the angle from the robot's center to the main antenna
_antenna_distance
instance-attribute
¶
_antenna_distance = sqrt(x ** 2 + y ** 2)
the distance from the robot's center to the main antenna
_convert_to_decimal
staticmethod
¶
_convert_to_decimal(coord: str, direction: str) -> float
Convert a coordinate in the format DDMM.mmmm to decimal degrees.
:param coord: the coordinate to convert :param direction: the direction (N/S/E/W) :return: the coordinate in decimal degrees
Events¶
Name | Description |
---|---|
NEW_MEASUREMENT | a new measurement has been received (argument: GnssMeasurement ) |
GnssSimulation ¶
GnssSimulation(
*,
wheels: WheelsSimulation,
lat_std_dev: float = 0.01,
lon_std_dev: float = 0.01,
heading_std_dev: float = 0.01,
gps_quality: GpsQuality = GpsQuality.RTK_FIXED
)
Bases: Gnss
Simulation of a GNSS receiver.
:param wheels: the wheels to use for the simulation :param lat_std_dev: the standard deviation of the latitude in meters :param lon_std_dev: the standard deviation of the longitude in meters :param heading_std_dev: the standard deviation of the heading in degrees :param gps_quality: the quality of the GPS signal
Events¶
Name | Description |
---|---|
NEW_MEASUREMENT | a new measurement has been received (argument: GnssMeasurement ) |
Robot ¶
Robot(modules: list[Module])
Bases: ABC
A robot that consists of a number of modules.
It can be either a hardware robot or a simulation.
RobotBrain ¶
RobotBrain(
communication: Communication,
*,
enable_esp_on_startup: bool = True
)
This module manages the communication with a Zauberzeug Robot Brain.
It expects a communication object, which is used for the actual read and write operations. Besides providing some basic methods like configuring or restarting the microcontroller, it augments and verifies checksums for each message.
It also keeps track of the clock offset between the microcontroller and the host system, which is used to synchronize the hardware time with the system time. The clock offset is calculated by comparing the hardware time with the system time and averaging the differences over a number of samples. If the offset changes significantly, a notification is sent and the offset history is cleared.
Events¶
Name | Description |
---|---|
LINE_RECEIVED | a line has been received from the microcontroller (argument: line as string) |
FLASH_P0_COMPLETE | flashing p0 was successful and 'Replica complete' was received |
RobotHardware ¶
RobotHardware(
modules: list[Module], robot_brain: RobotBrain
)
Bases: Robot
A robot that consists of hardware modules.
It generates Lizard code, forwards output to the hardware modules and sends commands to the robot brain.
RobotSimulation ¶
RobotSimulation(modules: list[Module])
Bases: Robot
A robot that consists of simulated modules.
It regularly calls the step method of all modules to allow them to update their internal state.
SerialCommunication ¶
SerialCommunication(
*,
device_path: str | None = None,
baud_rate: int = 115200
)
Bases: Communication
This module implements a communication via a serial device with a given baud rate.
It contains a list of search paths for finding the serial device.
SerialHardware ¶
SerialHardware(
robot_brain: RobotBrain,
*,
name: str = "serial",
rx_pin: int = 26,
tx_pin: int = 27,
baud: int = 115200,
num: int = 1
)
Bases: ModuleHardware
The serial module represents a serial connection with another device.
WebCommunication ¶
WebCommunication()
Bases: Communication
Remote connection to the Robot Brain's ESP.
This makes it possible to keep developing on your fast computer while communicating with the hardware components connected to a physical Robot Brain.
Wheels ¶
Wheels(**kwargs)
Bases: Module
, ABC
This module represents wheels for a two-wheel differential drive.
Wheels can be moved using the drive
methods and provide measured velocities as an event.
Events¶
Name | Description |
---|---|
VELOCITY_MEASURED | new velocity measurements are available for processing (argument: list of velocities) |
WheelsHardware ¶
WheelsHardware(
robot_brain: RobotBrain,
*,
can: CanHardware,
name: str = "wheels",
left_can_address: int = 0,
right_can_address: int = 256,
m_per_tick: float = 0.01,
width: float = 0.5,
is_left_reversed: bool = False,
is_right_reversed: bool = False
)
Bases: Wheels
, ModuleHardware
This module implements wheels hardware.
Drive and stop commands are forwarded to a given Robot Brain. Velocities are read and emitted regularly.
Events¶
Name | Description |
---|---|
VELOCITY_MEASURED | new velocity measurements are available for processing (argument: list of velocities) |
WheelsSimulation ¶
WheelsSimulation(width: float = 0.5)
Bases: Wheels
, ModuleSimulation
This module simulates two wheels.
Drive and stop commands impact internal velocities (linear and angular). A simulated pose is regularly updated with these velocities, while the velocities are emitted as an event.
angular_velocity
instance-attribute
¶
angular_velocity: float = 0
The current angular velocity of the robot.
friction_factor
instance-attribute
¶
friction_factor: float = 0.0
The factor of friction for the wheels (0 = no friction, 1 = full friction).
inertia_factor
instance-attribute
¶
inertia_factor: float = 0.0
The factor of inertia for the wheels (0 = no inertia, 1 = full inertia).
is_blocking
instance-attribute
¶
is_blocking: bool = False
If True, the wheels are blocking and the robot will not move.
linear_velocity
instance-attribute
¶
linear_velocity: float = 0
The current linear velocity of the robot.
pose
instance-attribute
¶
pose: Pose = Pose(time=time())
Provides the actual pose of the robot which can alter due to slippage.
slip_factor_left
instance-attribute
¶
slip_factor_left: float = 0
The factor of slippage for the left wheel (0 = no slippage, 1 = full slippage).
slip_factor_right
instance-attribute
¶
slip_factor_right: float = 0
The factor of slippage for the right wheel (0 = no slippage, 1 = full slippage).
width
instance-attribute
¶
width: float = width
The distance between the wheels -- used to calculate actual drift when slip_factor_* is used.
Events¶
Name | Description |
---|---|
VELOCITY_MEASURED | new velocity measurements are available for processing (argument: list of velocities) |