simulation.src.gazebo_simulation.src.automatic_drive.node module¶
Reference¶
-
class
DrivingState(distance_driven: float, time: float)[source]¶ Bases:
object-
distance_driven: float¶
-
time: float¶
-
-
class
AutomaticDriveNode[source]¶ Bases:
simulation.utils.ros_base.node_base.NodeBaseROS node to drive the car along the right side of the road.
Instead of directly modifying the car’s position and speed. The vehicle_simulation’s output is emulated. I.e. the transform from the vehicle to it’s world coordinate system is published and a state_estimation message published.
This enables to use the vehicle_simulation_link_node to move the car and only replace KITcar_brain + vehicle_simulation!
-
pub_tf¶ Publishes the new vehicle/world transform.
- Type
rospy.publisher
-
state_estimation_publisher¶ Publishes state estimation messages.
- Type
rospy.Publisher
-
section_proxy¶ Connection to groundtruth section service.
- Type
rospy.ServiceProxy
-
lane_proxy¶ Connection to groundtruth lane service.
- Type
rospy.ServiceProxy
-
_driving_state¶ Keep track of time and distance along the road.
- Type
-
property
driving_line¶ Line where car drives.
And points to stop at.
- Type
Tuple[Line, List[List[float]]]
-
update_state_estimation(speed: simulation.utils.geometry.vector.Vector, yaw_rate: float)[source]¶ Publish new state estimation message.
- Parameters
speed – Current speed in vehicle coordinates.
yaw_rate – Yaw rate of the car.
-
update_world_vehicle_tf(vehicle_world_tf: simulation.utils.geometry.transform.Transform)[source]¶ Publish up to date world to vehicle transformation to /tf.
- Parameters
vehicle_world_tf (Transform) – Transformation between vehicle and world frames.
-