Bridge Client
The bridge client gets information about the simulation world, actors and the ego vehicle from the Carla simulation server. It also receives the control commands as supplied by the ADS (Automated Driving System) and applies it to the simulated ego vehicle.
The bridge client consists of two files, bridgeClient.py and apolloEncode.py. The former handles communication with the bridge server and the latter handles encoding of messages into formats compatible with the Baidu Apollo ADS.
bridgeClient.py
src.sim.bridgeClient.ApolloBridgeClient_ActorGTPublisher(hostIP, hostPort)
Bases: BridgeClient
Generic Bridge Client
Parameters:
-
hostIP
(string
) –The IP of the ADS host (server)
-
hostPort
(int
) –The port of the ADS host (server)
src.sim.bridgeClient.ApolloBridgeClient_ActorGTPublisher.sendActorGroundTruth(dataList)
Function to send actor ground truth data from the simulator
Parameters:
-
dataList
(tuple
) –Contains all parameters regarding actors in the simulation frame
src.sim.bridgeClient.ApolloBridgeClient_ActorGTPublisher.sendSensorData(data, type)
Wrapper function to send sensor data using the netstruct protocol
Parameters:
-
data
(bytestring
) –Sensor data as a bytestring
-
type
(string
) –String specifying type of sensor data
src.sim.bridgeClient.ApolloBridgeClient_EgoPublisher(hostIP, hostPort)
Bases: BridgeClient
Generic Bridge Client
Parameters:
-
hostIP
(string
) –The IP of the ADS host (server)
-
hostPort
(int
) –The port of the ADS host (server)
src.sim.bridgeClient.ApolloBridgeClient_EgoPublisher.sendEgoData(dataList)
Function to send ego vehicle localization and other data to the ADS. Some of the localization messages are not sent, as specified by the 'enableLocMsgs' flag. This is because Apollo does not need all the localization messages to drive.
Parameters:
-
dataList
(tuple
) –Contains all parameters regarding the ego in the simulation frame
src.sim.bridgeClient.ApolloBridgeClient_ImgPublisher(hostIP, hostPort)
Bases: BridgeClient
Generic Bridge Client
Parameters:
-
hostIP
(string
) –The IP of the ads host (server)
-
hostPort
(int
) –The port of the ads host (server)
src.sim.bridgeClient.ApolloBridgeClient_ImgPublisher.sendImgData(imgData)
Function to send image data from simulator to ADS
Parameters:
-
imgData
–Image data from the simulator
src.sim.bridgeClient.ApolloBridgeClient_ImgPublisher.sendcImgData(cimgData)
Function to send compressed image data from simulator to ADS
Parameters:
-
cimgData
–Compressed image data from the simulator
src.sim.bridgeClient.ApolloBridgeClient_PCPublisher(hostIP, hostPort)
Bases: BridgeClient
Generic Bridge Client
Parameters:
-
hostIP
(string
) –The IP of the ads host (server)
-
hostPort
(int
) –The port of the ads host (server)
src.sim.bridgeClient.ApolloBridgeClient_PCPublisher.sendPCData(PCData)
Function to send pointcloud data from simulator to ADS
Parameters:
-
cimgData
–Compressed image data from the simulator
src.sim.bridgeClient.ApolloBridgeClient_Subscriber(hostIP, hostPort)
Bases: BridgeClient
Generic Bridge Client
Parameters:
-
hostIP
(string
) –The IP of the ads host (server)
-
hostPort
(int
) –The port of the ads host (server)
src.sim.bridgeClient.ApolloBridgeClient_Subscriber.decodeSimData(binMsg)
Function to decode the control command data received from the ADS
Parameters:
-
binMsg
(bytestring
) –Binary message from the ADS to be decoded
src.sim.bridgeClient.BridgeClient(hostIP, hostPort, msgString, delay=None, nextMsgTime=None)
Generic Bridge Client
Parameters:
-
hostIP
(string
) –The IP of the ads host (server)
-
hostPort
(int
) –The port of the ads host (server)
-
msgString
(bstring
) –string ID of the client
-
delay
(float
, default:None
) –time delay between each message
-
nextMsgTime
(float
, default:None
) –store the expected timestamp of the next message
src.sim.bridgeClient.BridgeClient.closeConnection()
Close the connection to the server
src.sim.bridgeClient.BridgeClient.computeNextMsgTime(now, prevMsg, delay)
When a message is sent, determines the timestamp of the next message and wheter to skip frames in case of excessive accumulation
Parameters:
-
now
(float
) –Current timestamp
-
prevMsg
(float
) –Expected time of the previous message
-
delay
(float
) –Expected delay of this message stream
Returns:
src.sim.bridgeClient.BridgeClient.connectToServer()
Initiate connection
src.sim.bridgeClient.BridgeClient.decodeSimData(binMsg)
Decodes and return the message received from the server, to be customized based on the client role.
src.sim.bridgeClient.BridgeClient.recvMsg()
Netstruct function to receive message from apolloBridgeServer
src.sim.bridgeClient.BridgeClient.recvSimData()
Function to receive messages from the server
Returns:
-
–
The message from the server, decoded with self.decodeSimData
src.sim.bridgeClient.BridgeClient.register()
Register a client object to the server
src.sim.bridgeClient.BridgeClient.sendBinMsg(data, msgType)
Netstruct protocol function to package and send binary data
Parameters:
-
data
(bytestring
) –The data to send
-
msgType
(string
) –Message type
apolloEncode.py
src.sim.apolloEncode.ConvertPoints(carlaPoint, t)
Convert Carla points from the pointcloud to the Protobuf PointXYZIT format
Parameters:
-
carlaPoint
–Point from each Carla pointcloud frame
-
t
(float
) –Timestamp
Returns:
-
–
Point in the PointXYZIT format
src.sim.apolloEncode.encode_BPmsgs(lat, lon, utmx, utmy, t, seq)
Package and serialize ego vehicle Best Pose data from the simulator to Apollo's format
Parameters:
-
lat
(float
) –Latitude
-
lon
(float
) –Longitude
-
utmx
(float
) –UTM X-coordinate
-
utmy
(float
) –UTM Y-coordinate
-
t
(float
) –Timestamp
-
seq
(int
) –Sequence number
Returns:
-
–
Best Pose message as a bytestring
src.sim.apolloEncode.encode_Chamsgs(t, lat, lon, utmx, utmy, odo, heading, vel, throttle, brake, steering)
Package and serialize ego vehicle chassis data from the simulator to Apollo's format
Parameters:
-
t
(float
) –Timestamp
-
lat
(float
) –Latitude
-
lon
(float
) –Longitude
-
utmx
(float
) –UTM X-coordinate
-
utmy
(float
) –UTM Y-coordinate
-
odo
(float
) –Odometer reading
-
heading
(float
) –Heading
-
vel
(float
) –Absolute velocity
-
throttle
(float
) –Throttle percentage
-
brake
(float
) –Brake percentage
-
steering
(float
) –Steering angle
Returns:
-
–
Chassis message as a bytestring
src.sim.apolloEncode.encode_CompressedIMG(imgData, seq)
Package and serialize compressed camera images from the simulator to Apollo's format
Parameters:
-
imgData
–Image data from the simulator
-
seq
(int
) –Sequence number
Returns:
-
–
Compressed image data as a bytestring
src.sim.apolloEncode.encode_GPSmsg(lat, lon, utmx, utmy, qw, qx, qy, qz, velx, vely, heading, t, seq)
Package and serialize ego vehicle GPS data from the simulator to Apollo's format
Parameters:
-
lat
(float
) –Latitude
-
lon
(float
) –Longitude
-
utmx
(float
) –UTM X-coordinate
-
utmy
(float
) –UTM Y-coordinate
-
qw
(float
) –Quaternion W
-
qx
(float
) –Quaternion X
-
qy
(float
) –Quaternion Y
-
qz
(float
) –Quaternion Z
-
velx
(float
) –Velocity in X-axis
-
vely
(float
) –Velocity in Y-axis
-
heading
(float
) –Heading
-
t
(float
) –Timestamp
-
seq
(int
) –Sequence number
Returns:
-
–
GPS message as a bytestring
src.sim.apolloEncode.encode_Heamsgs(t, seq, heading)
Package and serialize ego vehicle heading from the simulator to Apollo's format
Parameters:
-
t
(float
) –Timestamp
-
seq
(int
) –Sequence number
-
heading
(float
) –Heading
Returns:
-
–
Heading message as a bytestring
src.sim.apolloEncode.encode_IMG(imgData, seq)
Package and serialize camera images from the simulator to Apollo's format
Parameters:
-
imgData
–Image data from the simulator
-
seq
(int
) –Sequence number
Returns:
-
–
Image data as a bytestring
src.sim.apolloEncode.encode_IMUmsgs(avelX, avelY, avelZ, accX, accY, accZ, t, seq)
Package and serialize ego vehicle IMU data from the simulator to Apollo's format
Parameters:
-
avelX
(float
) –Angular velocity in the X-axis
-
avelY
(float
) –Angular velocity in the Y-axis
-
avelZ
(float
) –Angular velocity in the Z-axis
-
accX
(float
) –Acceleration in the X-axis
-
accY
(float
) –Acceleration in the Y-axis
-
accZ
(float
) –Acceleration in the Z-axis
-
t
(float
) –Timestamp
-
seq
(int
) –Sequence number
Returns:
-
–
IMU message as a bytestring
src.sim.apolloEncode.encode_INSmsgs(t, seq)
Package and serialize ego vehicle INS data from the simulator to Apollo's format
Parameters:
-
t
(float
) –Timestamp
-
seq
(int
) –Sequence number
Returns:
-
–
INS message as a bytestring
src.sim.apolloEncode.encode_PC(pcData, seq)
Package and serialize LiDAR pointcloud from the simulator to Apollo's format
Parameters:
-
pcData
–Pointcloud data from the simulator
-
seq
(int
) –Sequence number
Returns:
-
–
Pointcloud message as a bytestring
src.sim.apolloEncode.encode_POmsgs(objCount, objIDs, objType, objHeadings, objLats, objLons, objutmx, objutmy, objVelXs, objVelYs, objBBxs, objBBys, objBBzs, t, seq)
Package and serialize actor snapshot data from the simulator into Apollo's Perception Obstacle message
Parameters:
-
objCount
(int
) –Number of objects/obstacles in current simulation snapshot
-
objIDs
(list
) –Unique identifier assigned to each object/obstacle
-
objType
(string
) –Type of object (vehicle, pedestrian, cones etc.)
-
objHeadings
(float
) –Heading of each object
-
objLats
(float
) –Latitude of each object
-
objLons
(float
) –Longitude of each object
-
objutmx
(float
) –UTM X-coordinate of each object
-
objutmy
(float
) –UTM Y-coordinate of each object
-
objVelXs
(float
) –Velocity of each object in the X-axis
-
objVelYs
(float
) –Velocity of each object in the Y-axis
-
objBBxs
(float
) –Bounding box dimension of each object in the X-axis
-
objBBys
(float
) –Bounding box dimension of each object in the Y-axis
-
objBBzs
(float
) –Bounding box dimension of each object in the Z-axis
-
t
(float
) –Timestamp
-
seq
(int
) –Sequence number
Returns: Perception Obstacles message as a bytestring
src.sim.apolloEncode.encode_Posemsgs(lat, lon, utmx, utmy, qw, qx, qy, qz, velx, vely, heading, avelX, avelY, avelZ, accX, accY, accZ, t, seq)
Package and serialize ego vehicle pose from the simulator to Apollo's format
Parameters:
-
lat
(float
) –Latitude
-
lon
(float
) –Longitude
-
utmx
(float
) –UTM X-coordinate
-
utmy
(float
) –UTM Y-coordinate
-
qw
(float
) –Quaternion W
-
qx
(float
) –Quaternion X
-
qy
(float
) –Quaternion Y
-
qz
(float
) –Quaternion Z
-
velx
(float
) –Velocity in X-axis
-
vely
(float
) –Velocity in Y-axis
-
heading
(float
) –Heading
-
avelX
(float
) –Angular velocity in X-axis
-
avelY
(float
) –Angular velocity in Y-axis
-
avelZ
(float
) –Angular velocity in Z-axis
-
accX
(float
) –Acceleration in X-axis
-
accY
(float
) –Acceleration in Y-axis
-
accZ
(float
) –Acceleration in Z-axis
-
t
(float
) –Timestamp
-
seq
(int
) –Sequence number
Returns:
-
–
Pose message as a bytestring
src.sim.apolloEncode.encode_Tfmsgs(utmx, utmy, eulx, euly, eulz, t, seq)
Package and serialize ego vehicle transform from the simulator to Apollo's format
Parameters:
-
utmx
(float
) –UTM X-coordinate
-
utmy
(float
) –UTM Y-coordinate
-
eulx
(float
) –Euler angle in the X-axis
-
euly
(float
) –Euler angle in the Y-axis
-
eulz
(float
) –Euler angle in the Z-axis
-
t
(float
) –Timestamp
-
seq
(int
) –Sequence number
Returns:
-
–
Transform message as a bytestring
src.sim.apolloEncode.encode_corrIMUmsgs(avelX, avelY, avelZ, eulX, eulY, eulZ, accX, accY, accZ, heading, t)
Package and serialize ego vehicle Corrected IMU data from the simulator to Apollo's format
Parameters:
-
avelX
(float
) –Angular velocity in the X-axis
-
avelY
(float
) –Angular velocity in the Y-axis
-
avelZ
(float
) –Angular velocity in the Z-axis
-
eulX
(float
) –Euler angle in the X-axis
-
eulY
(float
) –Euler angle in the Y-axis
-
eulZ
(float
) –Euler angle in the Z-axis
-
accX
(float
) –Acceleration in the X-axis
-
accY
(float
) –Acceleration in the Y-axis
-
accZ
(float
) –Acceleration in the Z-axis
-
heading
(float
) –Heading (yaw)
-
t
(float
) –Timestamp
Returns:
-
–
Corrected IMU message as a bytestring