KITcar Simulation
2021.07

Tutorials

  • Installation
  • Getting Started
  • master.launch
  • Drive in Simulation
  • Roads
  • Road Sections
  • Models and Sensors
  • Simulated Rosbags
  • Datasets
  • Cycle GAN
  • How to Write Tests Using the Simulation
  • Scan Real Roads

ROS Packages

  • gazebo_simulation
  • simulation_brain_link
    • simulation.src.simulation_brain_link.src.sensor_camera package
    • simulation.src.simulation_brain_link.src.sensor_tof package
    • simulation.src.simulation_brain_link.src.vehicle_simulation_link package
      • Submodules
      • simulation.src.simulation_brain_link.src.vehicle_simulation_link.node module
      • Module contents
    • Sensors
    • Dynamics
    • Coordinate Frames
  • simulation_evaluation
  • simulation_groundtruth

Python Packages

  • simulation.utils.basics package
  • simulation.utils.geometry package
  • simulation.utils.machine_learning package
  • simulation.utils.ros_base package
  • simulation.utils.road package
  • simulation.utils.urdf package

Docker Images

  • Docker Images

Mini - Talks

  • Names and Values in Python
  • Inheritance in Python
  • Continuous Integration using the Simulation
  • Just Use Tmux
  • Onboarding
KITcar Simulation
  • »
  • simulation_brain_link »
  • simulation.src.simulation_brain_link.src.vehicle_simulation_link package
  • View page source

simulation.src.simulation_brain_link.src.vehicle_simulation_link package¶

Submodules¶

simulation.src.simulation_brain_link.src.vehicle_simulation_link.node module¶

VehicleSimulationLinkNode.

Classes:

VehicleSimulationLinkNode()

ROS node to translate state_estimation messages into movement of the vehicle in Gazebo and provide a simulation to world transformation.

class VehicleSimulationLinkNode[source]¶

Bases: simulation.utils.ros_base.node_base.NodeBase

ROS node to translate state_estimation messages into movement of the vehicle in Gazebo and provide a simulation to world transformation.

Whenever the pose of the vehicle is updated and a new message is received the updated twist is calculated and published.

set_model_twist_publisher¶

Publishes the new twist on the model plugins set_twist topic.

Type

rospy.publisher

get_model_pose_subscriber¶

Receives the current pose of the model in Gazebo.

Type

rospy.subscriber

state_estimation_subscriber¶

Receives the state_estimation messages.

Type

rospy.subscriber

latest_state_estimation¶

Latest received state estimation message.

Type

StateEstimationMsg

sub_tf¶

Receive transformation updates

Type

rospy.subscriber

pub_tf¶

Publish updates about the world to simulation transformation

Type

rospy.publisher

vehicle_world_tf¶

Transformation between the vehicle and world coordinate frame.

Type

Transform

Methods:

start()

Start node.

stop()

Called when deactivating or shutting down the node.

receive_model_pose_cb(msg)

Receive new model pose.

state_estimation_cb(msg)

Receive new state estimation.

update_twist(state_estimation, …)

Update the vehicle’s twist with an update on the model plugins set_twist topic.

update_pose()

receive_tf(tf_msg)

Receive msg from the tf topic and extract the world to vehicle transformation.

update_simulation_world_tf(vehicle_simulation_tf)

Publish up to date simulation to world transformation to /tf.

start()[source]¶

Start node.

stop()[source]¶

Called when deactivating or shutting down the node.

receive_model_pose_cb(msg: geometry_msgs.msg._Pose.Pose)[source]¶

Receive new model pose.

state_estimation_cb(msg: simulation_brain_link.msg._State.State)[source]¶

Receive new state estimation.

update_twist(state_estimation: simulation_brain_link.msg._State.State, vehicle_simulation_rotation: pyquaternion.quaternion.Quaternion)[source]¶

Update the vehicle’s twist with an update on the model plugins set_twist topic.

Parameters
  • state_estimation (StateEstimationMsg) – latest state estimation message

  • vehicle_simulation_rotation (Transform) – latest update of the rotation between the simulation and vehicle coordinate frames

update_pose()[source]¶
receive_tf(tf_msg: tf2_msgs.msg._TFMessage.TFMessage)[source]¶

Receive msg from the tf topic and extract the world to vehicle transformation.

update_simulation_world_tf(vehicle_simulation_tf: simulation.utils.geometry.transform.Transform)[source]¶

Publish up to date simulation to world transformation to /tf.

Parameters

vehicle_simulation_tf (Transform) – Transformation between vehicle and simulation frames.

Module contents¶

Next Previous

© Copyright 2021, KITcar.

Built with Sphinx using a theme provided by Read the Docs.