simulation.src.gazebo_simulation.src.car_state package

Submodules

simulation.src.gazebo_simulation.src.car_state.node module

Classes:

CarStateNode()

ROS node which publishes information about the model in a CarState.

class CarStateNode[source]

Bases: simulation.utils.ros_base.node_base.NodeBase

ROS node which publishes information about the model in a CarState.

car_frame

Frame of car in vehicle coordinate system

Type

shapely.geom.Polygon

model_pose_subscriber

Receive the cars pose

Type

rospy.Subscriber

model_twist_subscriber

Receive the cars twist

Type

rospy.Subscriber

get_vehicle_twist (Callable[[],None]

Returns current vehicle twist by calling the service proxy

publisher

CarStateMsg) publishes real time information about the car

Type

rospy.publisher

Methods:

receive_pose(pose)

receive_twist(twist)

start()

Start node.

stop()

Turn off node.

read_car_config()

Process car parameters.

state_update()

Publish new CarState with updated information.

receive_pose(pose)[source]
receive_twist(twist)[source]
start()[source]

Start node.

stop()[source]

Turn off node.

read_car_config()[source]

Process car parameters.

state_update()[source]

Publish new CarState with updated information.

simulation.src.gazebo_simulation.src.car_state.visualization module

Classes:

CarStateVisualizationNode()

ROS node which allows to visualize the car state in rviz.

class CarStateVisualizationNode[source]

Bases: simulation.utils.ros_base.node_base.NodeBase

ROS node which allows to visualize the car state in rviz.

frame_publisher

Publishes the cars frame as a rviz marker.

Type

rospy.publisher

view_cone_publisher

Publishes the cars view cone as rviz marker.

Type

rospy.publisher

state_subscriber

Subscribes to car_state

Type

rospy.subscriber

Methods:

start()

Start visualization.

stop()

Stop visualization.

state_cb(msg)

Call when car state is published.

start()[source]

Start visualization.

stop()[source]

Stop visualization.

state_cb(msg: gazebo_simulation.msg._CarState.CarState)[source]

Call when car state is published.

Parameters

msg (CarStateMsg) – Msg published by car state node

Module contents

The CarStateNode publishes up to date information about the simulated vehicle.

Thereby allowing easy access to the vehicle’s position and speed, but also the vehicle’s frame and view cone.

The CarStateVisualizationNode then processes this information and publishes messages which can be displayed in RVIZ.

Classes:

CarStateNode()

ROS node which publishes information about the model in a CarState.

CarStateVisualizationNode()

ROS node which allows to visualize the car state in rviz.

class CarStateNode[source]

Bases: simulation.utils.ros_base.node_base.NodeBase

ROS node which publishes information about the model in a CarState.

car_frame

Frame of car in vehicle coordinate system

Type

shapely.geom.Polygon

model_pose_subscriber

Receive the cars pose

Type

rospy.Subscriber

model_twist_subscriber

Receive the cars twist

Type

rospy.Subscriber

get_vehicle_twist (Callable[[],None]

Returns current vehicle twist by calling the service proxy

publisher

CarStateMsg) publishes real time information about the car

Type

rospy.publisher

Methods:

receive_pose(pose)

receive_twist(twist)

start()

Start node.

stop()

Turn off node.

read_car_config()

Process car parameters.

state_update()

Publish new CarState with updated information.

receive_pose(pose)[source]
receive_twist(twist)[source]
start()[source]

Start node.

stop()[source]

Turn off node.

read_car_config()[source]

Process car parameters.

state_update()[source]

Publish new CarState with updated information.

class CarStateVisualizationNode[source]

Bases: simulation.utils.ros_base.node_base.NodeBase

ROS node which allows to visualize the car state in rviz.

frame_publisher

Publishes the cars frame as a rviz marker.

Type

rospy.publisher

view_cone_publisher

Publishes the cars view cone as rviz marker.

Type

rospy.publisher

state_subscriber

Subscribes to car_state

Type

rospy.subscriber

Methods:

start()

Start visualization.

stop()

Stop visualization.

state_cb(msg)

Call when car state is published.

start()[source]

Start visualization.

stop()[source]

Stop visualization.

state_cb(msg: gazebo_simulation.msg._CarState.CarState)[source]

Call when car state is published.

Parameters

msg (CarStateMsg) – Msg published by car state node