simulation.src.gazebo_simulation.src.car_model package¶
Submodules¶
simulation.src.gazebo_simulation.src.car_model.camera_specs module¶
Classes:
|
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
andoutput_size
.
Attributes:
Rotation matrix of the camera.
Translation vector from vehicle to camera.
Matrix M.
Matrix A.
Matrix P.
Matrix H.
Translation vector to the camera in vehicle coordinates.
Translation vector to the camera in vehicle coordinates.
Vector of roll, pitch, yaw angles of the camera’s pose.
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
- property rpy: simulation.utils.geometry.vector.Vector¶
Vector of roll, pitch, yaw angles of the camera’s pose.
- Type
- property horizontal_fov: float¶
simulation.src.gazebo_simulation.src.car_model.car_specs module¶
Classes:
|
- 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:
Center of rear axle in COG coordinate frame.
Left rear tire in COG coordinate frame.
Right rear tire in COG coordinate frame.
Center of front axle in COG coordinate frame.
Left front tire in COG coordinate frame.
Right front tire in COG coordinate frame.
- 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
- property center_rear_left_tire: simulation.utils.geometry.point.Point¶
Left rear tire in COG coordinate frame.
- Type
- property center_rear_right_tire: simulation.utils.geometry.point.Point¶
Right rear tire in COG coordinate frame.
- Type
- property center_front_axle: simulation.utils.geometry.point.Point¶
Center of front axle in COG coordinate frame.
- Type
- property center_front_left_tire: simulation.utils.geometry.point.Point¶
Left front tire in COG coordinate frame.
- Type
- property center_front_right_tire: simulation.utils.geometry.point.Point¶
Right front tire in COG coordinate frame.
- Type
- 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:
|
Representation of the Dr. |
Functions:
|
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:
Chassis.
- TAG = 'robot'¶
- 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:
|
Classes:
|
- _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:
Methods:
with_default_properties
(name, origin)- name: str¶
- 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¶