simulation.src.gazebo_simulation.src.car_model package

Submodules

simulation.src.gazebo_simulation.src.car_model.camera_specs module

Classes:

CameraSpecs(focal_length_x, focal_length_y, …)

Camera specifications usually defined in kitcar-ros.

class CameraSpecs(focal_length_x: float, focal_length_y: float, optical_center_x: float, optical_center_y: float, r11: float, r12: float, r13: float, r21: float, r22: float, r23: float, r31: float, r32: float, r33: float, t1: float, t2: float, t3: float, capture_size: Dict[str, float] = <factory>, capture_format: str = 'R8G8B8', clip: Dict[str, float] = <factory>, output_size: Dict[str, float] = <factory>, update_rate: float = 60, image_topic: str = '/simulation/sensors/raw/camera', info_topic: str = '/simulation/sensors/camera/info')[source]

Bases: simulation.utils.basics.init_options.InitOptions

Camera specifications usually defined in kitcar-ros.

With this class, the real calibration is used to create the simulated camera model.

This way the camera specifications and calibration are very similar. The calibrations are still not exactly the same and therefore a separate calibration file is loaded!

There are, however, some nuances:

  • Instead of considering the complete calibration matrix, only the pitch angle is used to rotate the camera model around the y axis in simulation.

  • The real camera crops the image before publishing the image. This is reflected in the different capture_size and output_size.

Attributes:

capture_format

update_rate

image_topic

info_topic

R

Rotation matrix of the camera.

t

Translation vector from vehicle to camera.

M

Matrix M.

A

Matrix A.

P

Matrix P.

H

Matrix H.

t_vehicle

Translation vector to the camera in vehicle coordinates.

xyz

Translation vector to the camera in vehicle coordinates.

rpy

Vector of roll, pitch, yaw angles of the camera’s pose.

horizontal_fov

Methods:

simplify()

Create a simplified calibration from the real one.

save(file_path[, simplify, remove_clip, …])

Save to file.

focal_length_x: float
focal_length_y: float
optical_center_x: float
optical_center_y: float
r11: float
r12: float
r13: float
r21: float
r22: float
r23: float
r31: float
r32: float
r33: float
t1: float
t2: float
t3: float
capture_size: Dict[str, float]
capture_format: str = 'R8G8B8'
clip: Dict[str, float]
output_size: Dict[str, float]
update_rate: float = 60
image_topic: str = '/simulation/sensors/raw/camera'
info_topic: str = '/simulation/sensors/camera/info'
property R: numpy.matrix

Rotation matrix of the camera.

Type

np.matrix

property t: numpy.matrix

Translation vector from vehicle to camera.

In camera coordinates.

Type

np.ndarray

property M: numpy.matrix

Matrix M.

Transformation matrix from vehicle coordinates to camera coordinates.

Type

np.matrix

property A: numpy.matrix

Matrix A.

Transformation matrix from camera coordinates to pixels.

Type

np.matrix

property P: numpy.matrix

Matrix P.

Transformation matrix from vehicle coordinates to pixels.

Type

np.matrix

property H: numpy.matrix

Matrix H.

Transformation matrix from ground vehicle coordinates to pixels.

Type

np.matrix

property t_vehicle: numpy.ndarray

Translation vector to the camera in vehicle coordinates.

Type

np.ndarray

property xyz: simulation.utils.geometry.vector.Vector

Translation vector to the camera in vehicle coordinates.

Type

Vector

property rpy: simulation.utils.geometry.vector.Vector

Vector of roll, pitch, yaw angles of the camera’s pose.

Type

Vector

property horizontal_fov: float
simplify()[source]

Create a simplified calibration from the real one.

save(file_path: str, simplify=True, remove_clip=True, remove_sizes=True)[source]

Save to file.

Parameters
  • file_path – Path to file.

  • simplify – Simplify the car specs before saving.

  • remove_clip – Don’t save clip.

  • remove_sizes – Don’t save capture and output_size.

simulation.src.gazebo_simulation.src.car_model.car_specs module

Classes:

CarSpecs(wheelbase, track, vehicle_width, …)

class CarSpecs(wheelbase: float, track: float, vehicle_width: float, distance_cog_front: float, distance_cog_rear: float, cog_height: float, moment_of_inertia: float, tire_stiffness_front: float, tire_stiffness_rear: float, mass: float, tire_radius: float, distance_to_front_bumper: float, distance_to_rear_bumper: float, max_steering_angle_front_left: float, max_steering_angle_front_right: float, max_steering_angle_back_left: float, max_steering_angle_back_right: float, tire_mass: float = 0.5)[source]

Bases: simulation.utils.basics.init_options.InitOptions, simulation.utils.basics.save_options.SaveOptions

Attributes:

tire_mass

body_height

tire_width

center_rear_axle

Center of rear axle in COG coordinate frame.

center_rear_left_tire

Left rear tire in COG coordinate frame.

center_rear_right_tire

Right rear tire in COG coordinate frame.

center_front_axle

Center of front axle in COG coordinate frame.

center_front_left_tire

Left front tire in COG coordinate frame.

center_front_right_tire

Right front tire in COG coordinate frame.

steering_limit_rear

steering_limit_front

tire_dynamics

wheelbase: float
track: float
vehicle_width: float
distance_cog_front: float
distance_cog_rear: float
cog_height: float
moment_of_inertia: float
tire_stiffness_front: float
tire_stiffness_rear: float
mass: float
tire_radius: float
distance_to_front_bumper: float
distance_to_rear_bumper: float
max_steering_angle_front_left: float
max_steering_angle_front_right: float
max_steering_angle_back_left: float
max_steering_angle_back_right: float
tire_mass: float = 0.5
property body_height
property tire_width
property center_rear_axle: simulation.utils.geometry.point.Point

Center of rear axle in COG coordinate frame.

Type

Point

property center_rear_left_tire: simulation.utils.geometry.point.Point

Left rear tire in COG coordinate frame.

Type

Point

property center_rear_right_tire: simulation.utils.geometry.point.Point

Right rear tire in COG coordinate frame.

Type

Point

property center_front_axle: simulation.utils.geometry.point.Point

Center of front axle in COG coordinate frame.

Type

Point

property center_front_left_tire: simulation.utils.geometry.point.Point

Left front tire in COG coordinate frame.

Type

Point

property center_front_right_tire: simulation.utils.geometry.point.Point

Right front tire in COG coordinate frame.

Type

Point

property steering_limit_rear: simulation.utils.urdf.joint.JointLimit
property steering_limit_front: simulation.utils.urdf.joint.JointLimit
property tire_dynamics

simulation.src.gazebo_simulation.src.car_model.dr_drift module

Classes:

DrDrift(specs, camera_specs, tof_sensors, name)

Representation of the Dr.

Functions:

load_dr_drift(car_specs_path, …[, …])

Create a DrDrift instance with the information located in the provided files.

class DrDrift(specs: simulation.src.gazebo_simulation.src.car_model.car_specs.CarSpecs, camera_specs: simulation.src.gazebo_simulation.src.car_model.camera_specs.CameraSpecs, tof_sensors: List[simulation.src.gazebo_simulation.src.car_model.tof_sensors.TofSensor], name: str = 'dr_drift', version='1.0.0')[source]

Bases: simulation.utils.urdf.core.XmlObject

Representation of the Dr. Drift vehicle.

This class can be used to create a gazebo model of our Dr. Drift car. Within the initializer all pieces that make up the simulated model of Dr. Drift are created.

Information about the sensors’ specifications and positions are taken from the car_specs ROS package located in KITcar_brain.

Attributes:

TAG

version

Chassis.

TAG = 'robot'
name: simulation.utils.urdf.core.Attribute
version: simulation.utils.urdf.core.Attribute

Chassis.

load_dr_drift(car_specs_path: str, camera_specs_path: str, coordinate_systems_path: str, save_car_specs: Optional[str] = None, save_camera_calibration: Optional[str] = None, save_static_coordinates: Optional[str] = None)simulation.src.gazebo_simulation.src.car_model.dr_drift.DrDrift[source]

Create a DrDrift instance with the information located in the provided files.

Parameters
  • car_specs_path – Path to a yaml file that can be converted into a CarSpecs instance.

  • camera_specs_path – Path to a yaml file that can be converted into a CameraSpecs instance.

  • coordinate_systems_path – Path to a file defining the positions time of flight sensors.

  • save_car_specs – Path to where the resulting car_specs should be saved.

  • save_camera_calibration – Path to where the resulting camera calibration should be saved.

  • save_static_coordinates – Path to where the used static coordinate systems should be saved.

simulation.src.gazebo_simulation.src.car_model.tof_sensors module

Functions:

_get_depth_properties(name)

Classes:

TofSensor(name, origin, properties, size, mass)

_get_depth_properties(name: str)simulation.utils.urdf.camera.DepthCameraProperties[source]
class TofSensor(name: str, origin: simulation.utils.urdf.core.Origin, properties: simulation.utils.urdf.camera.DepthCameraProperties, size: simulation.utils.geometry.vector.Vector = Vector(0.02, 0.02, 0.02), mass: float = 1e-05)[source]

Bases: object

Attributes:

size

mass

full_name

Methods:

with_default_properties(name, origin)

name: str
origin: simulation.utils.urdf.core.Origin
properties: simulation.utils.urdf.camera.DepthCameraProperties
size: simulation.utils.geometry.vector.Vector = Vector(0.02, 0.02, 0.02)
mass: float = 1e-05
classmethod with_default_properties(name: str, origin: simulation.utils.urdf.core.Origin)simulation.src.gazebo_simulation.src.car_model.tof_sensors.TofSensor[source]
property full_name: str

Module contents