openpilot
opendbc
-
class CANParser
Public Functions
-
CANParser(int abus, const std::string &dbc_name, const std::vector<MessageParseOptions> &options, const std::vector<SignalParseOptions> &sigoptions)
-
void UpdateCans(uint64_t sec, const capnp::List<cereal::CanData>::Reader &cans)
-
void UpdateCans(uint64_t sec, const capnp::DynamicStruct::Reader &cans)
-
void UpdateValid(uint64_t sec)
Public Members
-
bool can_valid = false
-
bool bus_timeout = false
-
uint64_t first_sec = 0
-
uint64_t last_sec = 0
-
uint64_t last_nonempty_sec = 0
-
uint64_t bus_timeout_threshold = 0
-
uint64_t can_invalid_cnt = CAN_INVALID_CNT
Private Members
-
const int bus
-
kj::Array<capnp::word> aligned_buf
-
const DBC *dbc = NULL
-
std::unordered_map<uint32_t, MessageState> message_states
-
CANParser(int abus, const std::string &dbc_name, const std::vector<MessageParseOptions> &options, const std::vector<SignalParseOptions> &sigoptions)
- file common.h
- #include <map>#include <string>#include <utility>#include <unordered_map>#include <vector>#include <capnp/dynamic.h>#include <capnp/serialize.h>#include “cereal/gen/cpp/log.capnp.h”#include “opendbc/can/common_dbc.h”
- dir /home/batman/openpilot/opendbc/can
- dir /home/batman/openpilot/opendbc
cereal
messaging
-
class AlignedBuffer
Public Functions
-
kj::ArrayPtr<const capnp::word> align(const char *data, const size_t size)
-
kj::ArrayPtr<const capnp::word> align(const char *data, const size_t size)
-
class Context
Subclassed by MSGQContext, ZMQContext
-
class Message
Subclassed by MSGQMessage, ZMQMessage
-
class MessageBuilder : public MallocMessageBuilder
Public Functions
-
MessageBuilder()
-
cereal::Event::Builder initEvent(bool valid = true)
-
kj::ArrayPtr<capnp::byte> toBytes()
Private Members
-
kj::Array<capnp::word> heapArray_
-
MessageBuilder()
-
struct msgq_header_t
-
struct msgq_msg_t
-
struct msgq_pollitem_t
-
struct msgq_queue_t
Public Members
-
std::atomic<uint64_t> *num_readers
-
std::atomic<uint64_t> *write_pointer
-
std::atomic<uint64_t> *write_uid
-
std::atomic<uint64_t> *read_pointers[NUM_READERS]
-
std::atomic<uint64_t> *read_valids[NUM_READERS]
-
std::atomic<uint64_t> *read_uids[NUM_READERS]
-
char *mmap_p
-
char *data
-
size_t size
-
int reader_id
-
uint64_t read_uid_local
-
uint64_t write_uid_local
-
bool read_conflate
-
std::atomic<uint64_t> *num_readers
-
class MSGQMessage : public Message
Public Functions
-
void init(size_t size)
-
void init(char *data, size_t size)
-
void takeOwnership(char *data, size_t size)
-
size_t getSize()
-
char *getData()
-
void close()
-
~MSGQMessage()
Private Members
-
char *data
-
size_t size
-
void init(size_t size)
-
class MSGQPubSocket : public PubSocket
-
Private Members
-
msgq_queue_t *q = NULL
-
msgq_queue_t *q = NULL
-
class Poller
Subclassed by MSGQPoller, ZMQPoller
Public Functions
-
virtual ~Poller()
-
virtual ~Poller()
-
class PubMaster
Public Functions
-
int send(const char *name, capnp::byte *data, size_t size)
-
int send(const char *name, MessageBuilder &msg)
-
~PubMaster()
-
int send(const char *name, capnp::byte *data, size_t size)
-
class PubSocket
Subclassed by MSGQPubSocket, ZMQPubSocket
-
class SubMaster
Public Functions
-
SubMaster(const std::vector<const char*> &service_list, const std::vector<const char*> &poll = {}, const char *address = nullptr, const std::vector<const char*> &ignore_alive = {})
-
void update(int timeout = 1000)
-
void update_msgs(uint64_t current_time, const std::vector<std::pair<std::string, cereal::Event::Reader>> &messages)
-
void drain()
-
~SubMaster()
-
bool updated(const char *name) const
-
bool alive(const char *name) const
-
bool valid(const char *name) const
-
uint64_t rcv_frame(const char *name) const
-
uint64_t rcv_time(const char *name) const
-
cereal::Event::Reader &operator[](const char *name) const
Public Members
-
uint64_t frame = 0
-
SubMaster(const std::vector<const char*> &service_list, const std::vector<const char*> &poll = {}, const char *address = nullptr, const std::vector<const char*> &ignore_alive = {})
-
class SubSocket
Subclassed by MSGQSubSocket, ZMQSubSocket
-
class ZMQMessage : public Message
Public Functions
-
void init(size_t size)
-
void init(char *data, size_t size)
-
size_t getSize()
-
char *getData()
-
void close()
-
~ZMQMessage()
Private Members
-
char *data
-
size_t size
-
void init(size_t size)
- file impl_msgq.h
- #include <string>#include <vector>#include “cereal/messaging/messaging.h”#include “cereal/messaging/msgq.h”
Defines
-
MAX_POLLERS
-
MAX_POLLERS
- file impl_zmq.h
- #include <zmq.h>#include <string>#include <vector>#include “cereal/messaging/messaging.h”
Defines
-
MAX_POLLERS
-
MAX_POLLERS
- file messaging.h
- #include <cstddef>#include <map>#include <string>#include <vector>#include <utility>#include <time.h>#include <capnp/serialize.h>#include “cereal/gen/cpp/log.capnp.h”
Defines
-
MSG_MULTIPLE_PUBLISHERS
Functions
-
bool messaging_use_zmq()
-
MSG_MULTIPLE_PUBLISHERS
- file msgq.h
- #include <cstdint>#include <cstring>#include <string>#include <atomic>
Defines
-
DEFAULT_SEGMENT_SIZE
-
NUM_READERS
-
ALIGN(n)
-
UNUSED(x)
-
UNPACK64(higher, lower, input)
-
PACK64(output, higher, lower)
Functions
-
void msgq_wait_for_subscriber(msgq_queue_t *q)
-
void msgq_reset_reader(msgq_queue_t *q)
-
int msgq_msg_init_size(msgq_msg_t *msg, size_t size)
-
int msgq_msg_init_data(msgq_msg_t *msg, char *data, size_t size)
-
int msgq_msg_close(msgq_msg_t *msg)
-
int msgq_new_queue(msgq_queue_t *q, const char *path, size_t size)
-
void msgq_close_queue(msgq_queue_t *q)
-
void msgq_init_publisher(msgq_queue_t *q)
-
void msgq_init_subscriber(msgq_queue_t *q)
-
int msgq_msg_send(msgq_msg_t *msg, msgq_queue_t *q)
-
int msgq_msg_recv(msgq_msg_t *msg, msgq_queue_t *q)
-
int msgq_msg_ready(msgq_queue_t *q)
-
int msgq_poll(msgq_pollitem_t *items, size_t nitems, int timeout)
-
bool msgq_all_readers_updated(msgq_queue_t *q)
-
DEFAULT_SEGMENT_SIZE
- dir /home/batman/openpilot/cereal
- dir /home/batman/openpilot/cereal/messaging
visionipc
-
class VisionBuf
Public Functions
-
void allocate(size_t len)
-
void import()
-
void init_cl(cl_device_id device_id, cl_context ctx)
-
void init_rgb(size_t width, size_t height, size_t stride)
-
void init_yuv(size_t width, size_t height, size_t stride, size_t uv_offset)
-
int sync(int dir)
-
int free()
-
void set_frame_id(uint64_t id)
-
uint64_t get_frame_id()
Public Members
-
size_t len = 0
-
size_t mmap_len = 0
-
void *addr = nullptr
-
uint64_t *frame_id
-
int fd = 0
-
bool rgb = false
-
size_t width = 0
-
size_t height = 0
-
size_t stride = 0
-
size_t uv_offset = 0
-
uint8_t *y = nullptr
-
uint8_t *uv = nullptr
-
uint64_t server_id = 0
-
size_t idx = 0
-
VisionStreamType type
-
cl_mem buf_cl = nullptr
-
cl_command_queue copy_q = nullptr
-
int handle = 0
-
void allocate(size_t len)
-
class VisionIpcClient
Public Functions
-
VisionIpcClient(std::string name, VisionStreamType type, bool conflate, cl_device_id device_id = nullptr, cl_context ctx = nullptr)
-
~VisionIpcClient()
-
bool connect(bool blocking = true)
-
bool is_connected()
Public Static Functions
-
static std::set<VisionStreamType> getAvailableStreams(const std::string &name, bool blocking = true)
Private Functions
-
void init_msgq(bool conflate)
-
VisionIpcClient(std::string name, VisionStreamType type, bool conflate, cl_device_id device_id = nullptr, cl_context ctx = nullptr)
-
class VisionIpcServer
Public Functions
-
~VisionIpcServer()
-
VisionBuf *get_buffer(VisionStreamType type)
-
void create_buffers(VisionStreamType type, size_t num_buffers, bool rgb, size_t width, size_t height)
-
void create_buffers_with_sizes(VisionStreamType type, size_t num_buffers, bool rgb, size_t width, size_t height, size_t size, size_t stride, size_t uv_offset)
-
void start_listener()
Private Functions
-
void listener(void)
Private Members
-
cl_device_id device_id = nullptr
-
cl_context ctx = nullptr
-
uint64_t server_id
-
std::string name
-
std::map<VisionStreamType, std::atomic<size_t>> cur_idx
-
std::map<VisionStreamType, std::vector<VisionBuf*>> buffers
-
std::map<VisionStreamType, std::map<VisionBuf*, size_t>> idxs
-
Context *msg_ctx
-
std::map<VisionStreamType, PubSocket*> sockets
-
~VisionIpcServer()
- file ipc.h
- #include <cstddef>
- file visionbuf.h
- #include “cereal/visionipc/visionipc.h”#include <CL/cl.h>
Enums
Functions
-
void visionbuf_compute_aligned_width_and_height(int width, int height, int *aligned_w, int *aligned_h)
-
void visionbuf_compute_aligned_width_and_height(int width, int height, int *aligned_w, int *aligned_h)
- file visionipc_client.h
- #include <set>#include <string>#include <vector>#include <unistd.h>#include “cereal/messaging/messaging.h”#include “cereal/visionipc/visionipc.h”#include “cereal/visionipc/visionbuf.h”
- file visionipc_server.h
- #include <vector>#include <string>#include <thread>#include <atomic>#include <map>#include “cereal/messaging/messaging.h”#include “cereal/visionipc/visionipc.h”#include “cereal/visionipc/visionbuf.h”
Functions
-
std::string get_endpoint_name(std::string name, VisionStreamType type)
-
std::string get_endpoint_name(std::string name, VisionStreamType type)
- dir /home/batman/openpilot/cereal
- dir /home/batman/openpilot/cereal/visionipc
selfdrive
camerad
-
class CameraBuf
Public Functions
-
CameraBuf()
-
~CameraBuf()
-
void init(cl_device_id device_id, cl_context context, CameraState *s, VisionIpcServer *v, int frame_cnt, VisionStreamType yuv_type)
-
bool acquire()
-
void queue(size_t buf_idx)
Public Members
-
cl_command_queue q
-
FrameMetadata cur_frame_data
-
std::unique_ptr<FrameMetadata[]> camera_bufs_metadata
-
int rgb_width
-
int rgb_height
-
int rgb_stride
-
mat3 yuv_transform
Private Members
-
VisionIpcServer *vipc_server
-
Debayer *debayer = nullptr
-
VisionStreamType yuv_type
-
int cur_buf_idx
-
SafeQueue<int> safe_queue
-
int frame_buf_count
-
CameraBuf()
-
struct CameraInfo
-
class CameraState
Public Functions
-
void handle_camera_event(void *evdat)
-
void update_exposure_score(float desired_ev, int exp_t, int exp_g_idx, float exp_gain)
-
void set_camera_exposure(float grey_frac)
-
void sensors_start()
-
void camera_open(MultiCameraState *multi_cam_state, int camera_num, bool enabled)
-
void camera_set_parameters()
-
void camera_map_bufs(MultiCameraState *s)
-
void camera_init(MultiCameraState *s, VisionIpcServer *v, int camera_id, unsigned int fps, cl_device_id device_id, cl_context ctx, VisionStreamType yuv_type)
-
void camera_close()
Public Members
-
MultiCameraState *multi_cam_state
-
CameraInfo ci
-
bool enabled
-
int exposure_time
-
bool dc_gain_enabled
-
int dc_gain_weight
-
int gain_idx
-
float analog_gain_frac
-
int exposure_time_min
-
int exposure_time_max
-
float dc_gain_factor
-
int dc_gain_min_weight
-
int dc_gain_max_weight
-
float dc_gain_on_grey
-
float dc_gain_off_grey
-
float sensor_analog_gains[ANALOG_GAIN_MAX_CNT]
-
int analog_gain_min_idx
-
int analog_gain_max_idx
-
int analog_gain_rec_idx
-
int analog_gain_cost_delta
-
float analog_gain_cost_low
-
float analog_gain_cost_high
-
float cur_ev[3]
-
float min_ev
-
float max_ev
-
float best_ev_score
-
int new_exp_g
-
int new_exp_t
-
float measured_grey_fraction
-
float target_grey_fraction
-
float target_grey_factor
-
int camera_num
-
int32_t session_handle
-
int32_t sensor_dev_handle
-
int32_t isp_dev_handle
-
int32_t csiphy_dev_handle
-
int32_t link_handle
-
int buf0_handle
-
int buf_handle[FRAME_BUF_COUNT]
-
int sync_objs[FRAME_BUF_COUNT]
-
int request_ids[FRAME_BUF_COUNT]
-
int request_id_last
-
int frame_id_last
-
int idx_offset
-
bool skipped
-
int camera_id
Private Functions
-
void config_isp(int io_mem_handle, int fence, int request_id, int buf0_mem_handle, int buf0_offset)
-
void enqueue_req_multi(int start, int n, bool dp)
-
void enqueue_buffer(int i, bool dp)
-
int clear_req_queue()
-
int sensors_init()
-
void sensors_poke(int request_id)
-
void sensors_i2c(struct i2c_random_wr_payload *dat, int len, int op_code, bool data_word)
-
void handle_camera_event(void *evdat)
-
struct FrameMetadata
Public Members
-
uint32_t frame_id
-
unsigned int frame_length
-
uint64_t timestamp_sof
-
uint64_t timestamp_eof
-
unsigned int integ_lines
-
bool high_conversion_gain
-
float gain
-
float measured_grey_fraction
-
float target_grey_fraction
-
unsigned int lens_pos
-
float lens_err
-
float lens_true_pos
-
float processing_time
-
uint32_t frame_id
-
class MemoryManager
-
struct MultiCameraState
Public Members
-
unique_fd video0_fd
-
int device_iommu
-
int cdm_iommu
-
CameraState road_cam
-
CameraState wide_road_cam
-
CameraState driver_cam
-
unique_fd video0_fd
- file camera_common.h
- #include <cstdint>#include <cstdlib>#include <memory>#include <thread>#include “cereal/messaging/messaging.h”#include “cereal/visionipc/visionbuf.h”#include “cereal/visionipc/visionipc.h”#include “cereal/visionipc/visionipc_server.h”#include “common/mat.h”#include “common/queue.h”#include “common/swaglog.h”#include “system/hardware/hw.h”
Defines
-
CAMERA_ID_IMX298
-
CAMERA_ID_IMX179
-
CAMERA_ID_S5K3P8SP
-
CAMERA_ID_OV8865
-
CAMERA_ID_IMX298_FLIPPED
-
CAMERA_ID_OV10640
-
CAMERA_ID_LGC920
-
CAMERA_ID_LGC615
-
CAMERA_ID_AR0231
-
CAMERA_ID_OX03C10
-
CAMERA_ID_MAX
Typedefs
-
typedef struct CameraInfo CameraInfo
-
typedef struct FrameMetadata FrameMetadata
-
typedef void (*process_thread_cb)(MultiCameraState *s, CameraState *c, int cnt)
Functions
-
void fill_frame_data(cereal::FrameData::Builder &framed, const FrameMetadata &frame_data, CameraState *c)
-
float set_exposure_target(const CameraBuf *b, int x_start, int x_end, int x_skip, int y_start, int y_end, int y_skip)
-
std::thread start_process_thread(MultiCameraState *cameras, CameraState *cs, process_thread_cb callback)
-
void cameras_init(VisionIpcServer *v, MultiCameraState *s, cl_device_id device_id, cl_context ctx)
-
void cameras_open(MultiCameraState *s)
-
void cameras_run(MultiCameraState *s)
-
void cameras_close(MultiCameraState *s)
-
void camerad_thread()
-
int open_v4l_by_name_and_index(const char name[], int index = 0, int flags = O_RDWR | O_NONBLOCK)
Variables
-
const int YUV_BUFFER_COUNT = 40
-
const bool env_disable_road = getenv("DISABLE_ROAD") != NULL
-
const bool env_disable_wide_road = getenv("DISABLE_WIDE_ROAD") != NULL
-
const bool env_disable_driver = getenv("DISABLE_DRIVER") != NULL
-
const bool env_debug_frames = getenv("DEBUG_FRAMES") != NULL
-
const bool env_log_raw_frames = getenv("LOG_RAW_FRAMES") != NULL
-
const bool env_ctrl_exp_from_params = getenv("CTRL_EXP_FROM_PARAMS") != NULL
-
CAMERA_ID_IMX298
- file camera_qcom2.h
- #include <cstdint>#include <map>#include <utility>#include <media/cam_req_mgr.h>#include “system/camerad/cameras/camera_common.h”#include “system/camerad/cameras/camera_util.h”#include “common/params.h”#include “common/util.h”
Typedefs
-
typedef struct MultiCameraState MultiCameraState
-
typedef struct MultiCameraState MultiCameraState
- file camera_util.h
- #include <map>#include <mutex>#include <optional>#include <queue>#include <media/cam_req_mgr.h>
Functions
-
std::optional<int32_t> device_acquire(int fd, int32_t session_handle, void *data, uint32_t num_resources = 1)
-
int device_config(int fd, int32_t session_handle, int32_t dev_handle, uint64_t packet_handle)
-
int device_control(int fd, int op_code, int session_handle, int dev_handle)
-
int do_cam_control(int fd, int op_code, void *handle, int size)
-
void *alloc_w_mmu_hdl(int video0_fd, int len, uint32_t *handle, int align = 8, int flags = CAM_MEM_FLAG_KMD_ACCESS | CAM_MEM_FLAG_UMD_ACCESS | CAM_MEM_FLAG_CMD_BUF_TYPE, int mmu_hdl = 0, int mmu_hdl2 = 0)
-
void release(int video0_fd, uint32_t handle)
-
std::optional<int32_t> device_acquire(int fd, int32_t session_handle, void *data, uint32_t num_resources = 1)
- dir /home/batman/openpilot/system/camerad
- dir /home/batman/openpilot/system/camerad/cameras
- dir /home/batman/openpilot/system
-
class LapConv
- file utils.h
- #include <cstddef>#include <cstdint>#include <vector>#include “common/clutil.h”
Defines
-
NUM_SEGMENTS_X
-
NUM_SEGMENTS_Y
-
ROI_X_MIN
-
ROI_X_MAX
-
ROI_Y_MIN
-
ROI_Y_MAX
-
LM_THRESH
-
LM_PREC_THRESH
-
CONV_LOCAL_WORKSIZE
Functions
-
bool is_blur(const uint16_t *lapmap, const size_t size)
-
NUM_SEGMENTS_X
- dir /home/batman/openpilot/system/camerad
- dir /home/batman/openpilot/system/camerad/imgproc
- dir /home/batman/openpilot/system
locationd
-
class Localizer
Public Functions
-
Localizer()
-
Localizer(bool has_ublox)
-
int locationd_thread()
-
void reset_kalman(double current_time = NAN)
-
void reset_kalman(double current_time, Eigen::VectorXd init_orient, Eigen::VectorXd init_pos, Eigen::VectorXd init_vel, MatrixXdr init_pos_R, MatrixXdr init_vel_R)
-
void finite_check(double current_time = NAN)
-
void time_check(double current_time = NAN)
-
void update_reset_tracker()
-
bool is_gps_ok()
-
bool is_timestamp_valid(double current_time)
-
void determine_gps_mode(double current_time)
-
bool are_inputs_ok()
-
void observation_timings_invalid_reset()
-
kj::ArrayPtr<capnp::byte> get_message_bytes(MessageBuilder &msg_builder, bool inputsOK, bool sensorsOK, bool gpsOK, bool msgValid)
-
void build_live_location(cereal::LiveLocationKalman::Builder &fix)
-
Eigen::VectorXd get_position_geodetic()
-
Eigen::VectorXd get_state()
-
Eigen::VectorXd get_stdev()
-
void handle_msg_bytes(const char *data, const size_t size)
-
void handle_msg(const cereal::Event::Reader &log)
-
void handle_sensor(double current_time, const cereal::SensorEventData::Reader &log)
-
void handle_gps(double current_time, const cereal::GpsLocationData::Reader &log, const double sensor_time_offset)
-
void handle_gnss(double current_time, const cereal::GnssMeasurements::Reader &log)
-
void handle_car_state(double current_time, const cereal::CarState::Reader &log)
-
void handle_cam_odo(double current_time, const cereal::CameraOdometry::Reader &log)
-
void handle_live_calib(double current_time, const cereal::LiveCalibrationData::Reader &log)
-
void input_fake_gps_observations(double current_time)
Private Members
-
Eigen::VectorXd calib
-
bool calibrated = false
-
double car_speed = 0.0
-
double last_reset_time = NAN
-
int64_t unix_timestamp_millis = 0
-
double reset_tracker = 0.0
-
bool device_fell = false
-
bool gps_mode = false
-
double last_gps_msg = 0
-
bool ublox_available = true
-
bool observation_timings_invalid = false
-
bool standstill = true
-
int32_t orientation_reset_count = 0
-
Localizer()
-
class UbloxMsgParser
Public Functions
-
bool add_data(const uint8_t *incoming_data, uint32_t incoming_data_len, size_t &bytes_consumed)
-
void reset()
-
int needed_bytes()
-
kj::Array<capnp::word> gen_rxm_sfrbx(ubx_t::rxm_sfrbx_t *msg)
-
kj::Array<capnp::word> gen_rxm_rawx(ubx_t::rxm_rawx_t *msg)
-
kj::Array<capnp::word> gen_mon_hw(ubx_t::mon_hw_t *msg)
-
kj::Array<capnp::word> gen_mon_hw2(ubx_t::mon_hw2_t *msg)
-
bool add_data(const uint8_t *incoming_data, uint32_t incoming_data_len, size_t &bytes_consumed)
-
struct ubx_mga_ini_time_utc_t
-
namespace string_literals
-
namespace ublox
Functions
- struct ublox::ubx_mga_ini_time_utc_t ublox::__attribute__((packed))
- file locationd.h
- #include <eigen3/Eigen/Dense>#include <fstream>#include <memory>#include <map>#include <string>#include “cereal/messaging/messaging.h”#include “common/transformations/coordinates.hpp”#include “common/transformations/orientation.hpp”#include “common/params.h”#include “common/swaglog.h”#include “common/timing.h”#include “common/util.h”#include “selfdrive/sensord/sensors/constants.h”#include “selfdrive/locationd/models/live_kf.h”
Variables
- class Localizer __attribute__
- file ublox_msg.h
- #include <cassert>#include <cstdint>#include <memory>#include <string>#include <unordered_map>#include <ctime>#include “cereal/messaging/messaging.h”#include “common/util.h”#include “selfdrive/locationd/generated/gps.h”#include “selfdrive/locationd/generated/ubx.h”
Variables
-
uint8_t type
-
uint8_t version
-
uint8_t ref
-
int8_t leapSecs
-
uint16_t year
-
uint8_t month
-
uint8_t day
-
uint8_t hour
-
uint8_t minute
-
uint8_t second
-
uint8_t reserved1
-
uint32_t ns
-
uint16_t tAccS
-
uint16_t reserved2
-
uint32_t tAccNs
-
uint8_t type
- dir /home/batman/openpilot/selfdrive/locationd
- dir /home/batman/openpilot/selfdrive
ui
-
struct Alert
-
Public Members
-
QString text1
-
QString text2
-
QString type
-
cereal::ControlsState::AlertSize size
-
AudibleAlert sound
-
QString text1
-
class Device : public QObject
Public Functions
-
Device(QObject *parent = 0)
Private Functions
-
void setAwake(bool on)
-
Device(QObject *parent = 0)
-
struct UIScene
Public Members
-
bool calibration_valid = false
-
bool calibration_wide_valid = false
-
bool wide_cam = true
-
mat3 view_from_calib = DEFAULT_CALIBRATION
-
mat3 view_from_wide_calib = DEFAULT_CALIBRATION
-
cereal::PandaState::PandaType pandaType
-
float lane_line_probs[4]
-
float road_edge_stds[2]
-
QPolygonF track_vertices
-
QPolygonF lane_line_vertices[4]
-
QPolygonF road_edge_vertices[2]
-
QPointF lead_vertices[2]
-
float light_sensor
-
bool started
-
bool ignition
-
bool is_metric
-
bool map_on_left
-
bool longitudinal_control
-
uint64_t started_frame
-
bool calibration_valid = false
-
class UIState : public QObject
Public Functions
-
UIState(QObject *parent = 0)
-
void updateStatus()
-
bool worldObjectsVisible() const
-
bool engaged() const
Public Members
-
int fb_w = 0
-
int fb_h = 0
-
bool awake
-
int prime_type
-
QString language
-
QTransform car_space_transform
-
bool wide_cam_only
Private Slots
-
void update()
-
UIState(QObject *parent = 0)
- file ui.h
- #include <memory>#include <string>#include <optional>#include <QObject>#include <QTimer>#include <QColor>#include <QFuture>#include <QPolygonF>#include <QTransform>#include “cereal/messaging/messaging.h”#include “common/modeldata.h”#include “common/params.h”#include “common/timing.h”
Typedefs
-
typedef cereal::CarControl::HUDControl::AudibleAlert AudibleAlert
-
typedef enum UIStatus UIStatus
-
typedef struct UIScene UIScene
Enums
Functions
-
int get_path_length_idx(const cereal::ModelDataV2::XYZTData::Reader &line, const float path_height)
Variables
-
const int bdr_s = 30
-
const int header_h = 420
-
const int UI_FREQ = 20
-
const mat3 DEFAULT_CALIBRATION = {{0.0, 1.0, 0.0, 0.0, 0.0, 1.0, 1.0, 0.0, 0.0}}
- const QColor bg_colors [] = {[STATUS_DISENGAGED] = QColor(0x17, 0x33, 0x49, 0xc8),[STATUS_OVERRIDE] = QColor(0x91, 0x9b, 0x95, 0xf1),[STATUS_ENGAGED] = QColor(0x17, 0x86, 0x44, 0xf1),[STATUS_WARNING] = QColor(0xDA, 0x6F, 0x25, 0xf1),[STATUS_ALERT] = QColor(0xC9, 0x22, 0x31, 0xf1),}
-
typedef cereal::CarControl::HUDControl::AudibleAlert AudibleAlert
- dir /home/batman/openpilot/selfdrive
- dir /home/batman/openpilot/selfdrive/ui
soundd
-
class Sound : public QObject
Public Functions
-
Sound(QObject *parent = 0)
Protected Attributes
-
QMap<AudibleAlert, QPair<QSoundEffect*, int>> sounds
-
SubMaster sm
-
uint64_t started_frame
-
Sound(QObject *parent = 0)
- file sound.h
- #include <QMap>#include <QSoundEffect>#include <QString>#include “system/hardware/hw.h”#include “selfdrive/ui/ui.h”
Variables
-
const std::tuple<AudibleAlert, QString, int> sound_list[] = {{AudibleAlert::ENGAGE, "engage.wav", 0}, {AudibleAlert::DISENGAGE, "disengage.wav", 0}, {AudibleAlert::REFUSE, "refuse.wav", 0}, {AudibleAlert::PROMPT, "prompt.wav", 0}, {AudibleAlert::PROMPT_REPEAT, "prompt.wav", QSoundEffect::Infinite}, {AudibleAlert::PROMPT_DISTRACTED, "prompt_distracted.wav", QSoundEffect::Infinite}, {AudibleAlert::WARNING_SOFT, "warning_soft.wav", QSoundEffect::Infinite}, {AudibleAlert::WARNING_IMMEDIATE, "warning_immediate.wav", QSoundEffect::Infinite},}
-
const std::tuple<AudibleAlert, QString, int> sound_list[] = {{AudibleAlert::ENGAGE, "engage.wav", 0}, {AudibleAlert::DISENGAGE, "disengage.wav", 0}, {AudibleAlert::REFUSE, "refuse.wav", 0}, {AudibleAlert::PROMPT, "prompt.wav", 0}, {AudibleAlert::PROMPT_REPEAT, "prompt.wav", QSoundEffect::Infinite}, {AudibleAlert::PROMPT_DISTRACTED, "prompt_distracted.wav", QSoundEffect::Infinite}, {AudibleAlert::WARNING_SOFT, "warning_soft.wav", QSoundEffect::Infinite}, {AudibleAlert::WARNING_IMMEDIATE, "warning_immediate.wav", QSoundEffect::Infinite},}
- dir /home/batman/openpilot/selfdrive
- dir /home/batman/openpilot/selfdrive/ui/soundd
- dir /home/batman/openpilot/selfdrive/ui
replay
-
struct Camera
Public Members
-
CameraType type
-
VisionStreamType stream_type
-
int width
-
int height
-
SafeQueue<std::pair<FrameReader*, const cereal::EncodeIndex::Reader>> queue
-
int cached_id = -1
-
int cached_seg = -1
-
CameraType type
-
class CameraServer
Public Functions
-
CameraServer(std::pair<int, int> camera_size[MAX_CAMERAS] = nullptr)
-
~CameraServer()
-
void pushFrame(CameraType type, FrameReader *fr, const cereal::EncodeIndex::Reader &eidx)
-
void waitForSent()
Protected Attributes
- Camera cameras_ [MAX_CAMERAS] = {{.type = RoadCam, .stream_type = VISION_STREAM_ROAD},{.type = DriverCam, .stream_type = VISION_STREAM_DRIVER},{.type = WideRoadCam, .stream_type = VISION_STREAM_WIDE_ROAD},}
-
std::unique_ptr<VisionIpcServer> vipc_server_
-
CameraServer(std::pair<int, int> camera_size[MAX_CAMERAS] = nullptr)
-
class ConsoleUI : public QObject
-
Signals
-
void updateProgressBarSignal(uint64_t cur, uint64_t total, bool success)
-
void logMessageSignal(ReplyMsgType type, const QString &msg)
Private Types
Private Functions
-
void initWindows()
-
void handleKey(char c)
-
void displayHelp()
-
void displayTimelineDesc()
-
void updateTimeline()
-
void updateSummary()
-
void updateStatus()
-
void pauseReplay(bool pause)
Private Members
-
SubMaster sm
-
QBasicTimer getch_timer
-
QTimer sm_timer
-
QSocketNotifier notifier = {0, QSocketNotifier::Read, this}
-
int max_width
-
int max_height
Private Slots
-
void readyRead()
-
void timerEvent(QTimerEvent *ev)
-
void updateProgressBar(uint64_t cur, uint64_t total, bool success)
-
void logMessage(ReplyMsgType type, const QString &msg)
-
void updateProgressBarSignal(uint64_t cur, uint64_t total, bool success)
-
class Event
-
class FileReader
-
class FrameReader
Public Functions
-
FrameReader()
-
~FrameReader()
-
bool load(const std::string &url, bool no_hw_decoder = false, std::atomic<bool> *abort = nullptr, bool local_cache = false, int chunk_size = -1, int retries = 0)
-
bool load(const std::byte *data, size_t size, bool no_hw_decoder = false, std::atomic<bool> *abort = nullptr)
-
bool get(int idx, uint8_t *yuv)
-
int getYUVSize() const
-
size_t getFrameCount() const
-
bool valid() const
Private Functions
-
bool initHardwareDecoder(AVHWDeviceType hw_device_type)
-
bool decode(int idx, uint8_t *yuv)
-
AVFrame *decodeFrame(AVPacket *pkt)
-
bool copyBuffers(AVFrame *f, uint8_t *yuv)
Private Members
-
std::unique_ptr<AVFrame, AVFrameDeleter> av_frame_
-
std::unique_ptr<AVFrame, AVFrameDeleter> hw_frame
-
AVFormatContext *input_ctx = nullptr
-
AVCodecContext *decoder_ctx = nullptr
-
int key_frames_count_ = 0
-
bool valid_ = false
-
AVIOContext *avio_ctx_ = nullptr
-
AVPixelFormat hw_pix_fmt = AV_PIX_FMT_NONE
-
AVBufferRef *hw_device_ctx = nullptr
-
int prev_idx = -1
-
FrameReader()
-
struct lessThan
-
class LogReader
Public Functions
-
LogReader(size_t memory_pool_block_size = DEFAULT_EVENT_MEMORY_POOL_BLOCK_SIZE)
-
~LogReader()
Private Functions
-
LogReader(size_t memory_pool_block_size = DEFAULT_EVENT_MEMORY_POOL_BLOCK_SIZE)
-
class Replay : public QObject
Public Functions
-
Replay(QString route, QStringList allow, QStringList block, SubMaster *sm = nullptr, uint32_t flags = REPLAY_FLAG_NONE, QString data_dir = "", QObject *parent = 0)
-
~Replay()
-
bool load()
-
void start(int seconds = 0)
-
void stop()
-
void pause(bool pause)
-
void seekTo(double seconds, bool relative)
-
bool isPaused() const
-
void installEventFilter(replayEventFilter filter, void *opaque)
-
int segmentCacheLimit() const
-
void setSegmentCacheLimit(int n)
-
bool hasFlag(REPLAY_FLAGS flag) const
-
void addFlag(REPLAY_FLAGS flag)
-
void removeFlag(REPLAY_FLAGS flag)
-
double currentSeconds() const
-
QDateTime currentDateTime() const
-
uint64_t routeStartTime() const
-
int toSeconds(uint64_t mono_time) const
-
int totalSeconds() const
-
void setSpeed(float speed)
-
float getSpeed() const
-
const std::vector<std::tuple<int, int, TimelineType>> getTimeline()
Protected Functions
-
void stream()
-
void setCurrentSegment(int n)
-
void queueSegment()
-
void mergeSegments(const SegmentMap::iterator &begin, const SegmentMap::iterator &end)
-
void buildTimeline()
-
bool isSegmentMerged(int n)
Protected Attributes
-
QThread *stream_thread_ = nullptr
-
SegmentMap segments_
-
bool paused_ = false
-
bool events_updated_ = false
-
uint64_t route_start_ts_ = 0
-
SubMaster *sm = nullptr
-
std::vector<const char*> sockets_
-
std::unique_ptr<CameraServer> camera_server_
-
std::atomic<uint32_t> flags_ = REPLAY_FLAG_NONE
-
QFuture<void> timeline_future
-
std::vector<std::tuple<int, int, TimelineType>> timeline
-
float speed_ = 1.0
-
replayEventFilter event_filter = nullptr
-
void *filter_opaque = nullptr
-
int segment_cache_limit = MIN_SEGMENTS_CACHE
Protected Slots
-
void segmentLoadFinished(bool success)
-
Replay(QString route, QStringList allow, QStringList block, SubMaster *sm = nullptr, uint32_t flags = REPLAY_FLAG_NONE, QString data_dir = "", QObject *parent = 0)
-
class Route
Public Functions
-
Route(const QString &route, const QString &data_dir = {})
-
bool load()
-
const QString &name() const
-
const QDateTime datetime() const
-
const QString &dir() const
-
const RouteIdentifier &identifier() const
-
const std::map<int, SegmentFile> &segments() const
-
const SegmentFile &at(int n)
Public Static Functions
-
static RouteIdentifier parseRoute(const QString &str)
Protected Functions
-
bool loadFromLocal()
-
bool loadFromServer()
-
bool loadFromJson(const QString &json)
-
void addFileToSegment(int seg_num, const QString &file)
Protected Attributes
-
RouteIdentifier route_ = {}
-
QString data_dir_
-
std::map<int, SegmentFile> segments_
-
QDateTime date_time_
-
Route(const QString &route, const QString &data_dir = {})
-
struct RouteIdentifier
-
class Segment : public QObject
Public Functions
-
Segment(int n, const SegmentFile &files, uint32_t flags, const std::set<cereal::Event::Which> &allow = {})
-
~Segment()
-
bool isLoaded() const
Signals
-
void loadFinished(bool success)
-
Segment(int n, const SegmentFile &files, uint32_t flags, const std::set<cereal::Event::Which> &allow = {})
-
struct SegmentFile
- file camera.h
- #include <unistd.h>#include “cereal/visionipc/visionipc_server.h”#include “common/queue.h”#include “tools/replay/framereader.h”#include “tools/replay/logreader.h”
- file consoleui.h
- #include <array>#include <QBasicTimer>#include <QObject>#include <QSocketNotifier>#include <QTimer>#include <QTimerEvent>#include “tools/replay/replay.h”#include <ncurses.h>
- file filereader.h
- #include <atomic>#include <string>
- file framereader.h
- #include <memory>#include <string>#include <vector>#include “tools/replay/filereader.h”#include <libavcodec/avcodec.h>#include <libavformat/avformat.h>
- file logreader.h
- #include <set>#include “cereal/gen/cpp/log.capnp.h”#include “system/camerad/cameras/camera_common.h”#include “tools/replay/filereader.h”
Variables
-
const CameraType ALL_CAMERAS[] = {RoadCam, DriverCam, WideRoadCam}
-
const int MAX_CAMERAS = std::size(ALL_CAMERAS)
-
const int DEFAULT_EVENT_MEMORY_POOL_BLOCK_SIZE = 65000
-
const CameraType ALL_CAMERAS[] = {RoadCam, DriverCam, WideRoadCam}
- file replay.h
- #include <optional>#include <QThread>#include “tools/replay/camera.h”#include “tools/replay/route.h”
Enums
-
enum REPLAY_FLAGS
Values:
-
enumerator REPLAY_FLAG_NONE
-
enumerator REPLAY_FLAG_DCAM
-
enumerator REPLAY_FLAG_ECAM
-
enumerator REPLAY_FLAG_NO_LOOP
-
enumerator REPLAY_FLAG_NO_FILE_CACHE
-
enumerator REPLAY_FLAG_QCAMERA
-
enumerator REPLAY_FLAG_NO_HW_DECODER
-
enumerator REPLAY_FLAG_FULL_SPEED
-
enumerator REPLAY_FLAG_NO_VIPC
-
enumerator REPLAY_FLAG_NONE
-
enum REPLAY_FLAGS
- file route.h
- #include <QDateTime>#include <QFutureSynchronizer>#include “tools/replay/framereader.h”#include “tools/replay/logreader.h”#include “tools/replay/util.h”
- file util.h
- #include <atomic>#include <functional>#include <string>
Typedefs
-
typedef std::function<void(ReplyMsgType type, const std::string msg)> ReplayMessageHandler
Enums
Functions
-
void installMessageHandler(ReplayMessageHandler)
-
void logMessage(ReplyMsgType type, const char *fmt, ...)
-
void precise_nano_sleep(long sleep_ns)
-
std::string httpGet(const std::string &url, size_t chunk_size = 0, std::atomic<bool> *abort = nullptr)
-
void installDownloadProgressHandler(DownloadProgressHandler)
-
typedef std::function<void(ReplyMsgType type, const std::string msg)> ReplayMessageHandler
- dir /home/batman/openpilot/tools/replay
- dir /home/batman/openpilot/tools
qt
-
class AdvancedNetworking : public QWidget
Public Functions
-
AdvancedNetworking(QWidget *parent = 0, WifiManager *wifi = 0)
Signals
-
void backPress()
-
AdvancedNetworking(QWidget *parent = 0, WifiManager *wifi = 0)
-
class DeclinePage : public QFrame
Public Functions
-
DeclinePage(QWidget *parent = 0)
Signals
-
void getBack()
Private Functions
-
void showEvent(QShowEvent *event)
-
DeclinePage(QWidget *parent = 0)
-
class DevicePanel : public ListWidget
Public Functions
-
DevicePanel(SettingsWindow *parent)
Private Members
-
Params params
-
DevicePanel(SettingsWindow *parent)
-
class DriverViewScene : public QWidget
Public Functions
-
DriverViewScene(QWidget *parent)
Public Slots
-
void frameUpdated()
-
DriverViewScene(QWidget *parent)
-
class DriverViewWindow : public QWidget
Public Functions
-
DriverViewWindow(QWidget *parent)
Signals
-
void done()
Protected Functions
-
void mouseReleaseEvent(QMouseEvent *e)
-
DriverViewWindow(QWidget *parent)
-
class ExperimentalModeButton : public QPushButton
Public Functions
-
ExperimentalModeButton(QWidget *parent = 0)
Signals
-
void openSettings(int index = 0, const QString &toggle = "")
Protected Functions
-
void paintEvent(QPaintEvent *event)
Private Functions
-
void showEvent(QShowEvent *event)
-
ExperimentalModeButton(QWidget *parent = 0)
-
struct Network
Public Members
-
QByteArray ssid
-
unsigned int strength
-
ConnectedType connected
-
SecurityType security_type
-
QByteArray ssid
-
class Networking : public QFrame
Public Functions
-
Networking(QWidget *parent = 0, bool show_advanced = true)
Public Members
-
WifiManager *wifi = nullptr
Public Slots
-
void refresh()
Private Members
-
QStackedLayout *main_layout = nullptr
-
QWidget *wifiScreen = nullptr
-
AdvancedNetworking *an = nullptr
-
Networking(QWidget *parent = 0, bool show_advanced = true)
-
class OnboardingWindow : public QStackedWidget
Public Functions
-
OnboardingWindow(QWidget *parent = 0)
-
void showTrainingGuide()
-
bool completed() const
Signals
-
void onboardingDone()
Private Functions
-
void updateActiveScreen()
-
OnboardingWindow(QWidget *parent = 0)
-
class SettingsWindow : public QFrame
Public Functions
-
SettingsWindow(QWidget *parent = 0)
-
void setCurrentPanel(int index, const QString ¶m = "")
Signals
-
void closeSettings()
-
void reviewTrainingGuide()
-
void showDriverView()
-
void expandToggleDescription(const QString ¶m)
Protected Functions
-
SettingsWindow(QWidget *parent = 0)