simulation.src.simulation_brain_link.src.vehicle_simulation_link package¶
Submodules¶
simulation.src.simulation_brain_link.src.vehicle_simulation_link.node module¶
VehicleSimulationLinkNode.
Classes:
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
Methods:
start
()Start node.
stop
()Called when deactivating or shutting down the node.
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.
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.
- 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
- 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.