From ab83e48ec4f7c7ddaa742d9797b0d38646fdb268 Mon Sep 17 00:00:00 2001 From: Adeeb <8762862+adeebshihadeh@users.noreply.github.com> Date: Wed, 3 Jun 2020 12:54:49 -0700 Subject: [PATCH] Add pre-commit hooks (#1629) --- .pre-commit-config.yaml | 4 ++ SAFETY.md | 4 +- common/transformations/README.md | 6 +- selfdrive/camerad/cameras/camera_qcom2.c | 16 ++--- selfdrive/camerad/cameras/sensor2_i2c.h | 4 +- selfdrive/camerad/imgproc/conv.cl | 12 ++-- selfdrive/camerad/imgproc/pool.cl | 4 +- selfdrive/camerad/transforms/rgb_to_yuv.c | 2 +- selfdrive/common/buffering.c | 4 +- selfdrive/common/framebuffer.cc | 2 +- selfdrive/locationd/paramsd.cc | 2 +- selfdrive/loggerd/frame_logger.h | 2 +- selfdrive/loggerd/loggerd.cc | 2 +- selfdrive/modeld/modeld.cc | 2 +- selfdrive/modeld/thneed/debug/main.cc | 6 +- .../thneed/debug/microbenchmark/gemm_image.cl | 4 +- .../modeld/thneed/debug/microbenchmark/go.c | 4 +- selfdrive/ui/text/text.c | 2 +- tools/lib/vidindex/vidindex.c | 6 +- tools/nui/FileReader.cpp | 2 +- tools/nui/Unlogger.cpp | 4 +- tools/nui/main.cpp | 18 ++--- tools/nui/nui | 1 - tools/sim/README.md | 10 +-- tools/sim/start_carla.sh | 2 +- tools/webcam/README.md | 70 +++++++++---------- 26 files changed, 99 insertions(+), 96 deletions(-) diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index e559d87b..d6319e48 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -6,6 +6,10 @@ repos: - id: check-json - id: check-xml - id: check-yaml + - id: check-merge-conflict + - id: check-symlinks + - id: trailing-whitespace + exclude: '^(pyextra)|(external)|(cereal)|(rednose)|(panda)|(laika)|(opendbc)|(laika_repo)|(rednose_repo)|(phonelibs)|(lib_mpc_export)/' - repo: https://github.com/pre-commit/mirrors-mypy rev: master hooks: diff --git a/SAFETY.md b/SAFETY.md index 5a3c287f..9cf8933b 100644 --- a/SAFETY.md +++ b/SAFETY.md @@ -1,7 +1,7 @@ openpilot Safety ====== -openpilot is an Adaptive Cruise Control (ACC) and Automated Lane Centering (ALC) system. +openpilot is an Adaptive Cruise Control (ACC) and Automated Lane Centering (ALC) system. Like other ACC and ALC systems, openpilot is a failsafe passive system and it requires the driver to be alert and to pay attention at all times. @@ -22,7 +22,7 @@ hardware-in-the-loop and in-vehicle tests before each software release. Following Hazard and Risk Analysis and FMEA, at a very high level, we have designed openpilot ensuring two main safety requirements. -1. The driver must always be capable to immediately retake manual control of the vehicle, +1. The driver must always be capable to immediately retake manual control of the vehicle, by stepping on either pedal or by pressing the cancel button. 2. The vehicle must not alter its trajectory too quickly for the driver to safely react. This means that while the system is engaged, the actuators are constrained diff --git a/common/transformations/README.md b/common/transformations/README.md index 119dae63..dd9cdcc7 100644 --- a/common/transformations/README.md +++ b/common/transformations/README.md @@ -25,14 +25,14 @@ by generating a rotation matrix and multiplying. Orientation Conventations ------ -Quaternions, rotation matrices and euler angles are three +Quaternions, rotation matrices and euler angles are three equivalent representations of orientation and all three are used throughout the code base. For euler angles the preferred convention is [roll, pitch, yaw] which corresponds to rotations around the [x, y, z] axes. All euler angles should always be in radians or radians/s unless -for plotting or display purposes. For quaternions the hamilton +for plotting or display purposes. For quaternions the hamilton notations is preferred which is [qw, qx, qy, qz]. All quaternions should always be normalized with a strictly positive qw. **These quaternions are a unique representation of orientation whereas euler angles @@ -49,7 +49,7 @@ EONs are not all mounted in the exact same way. To compensate for the effects of Example ------ -To transform global Mesh3D positions and orientations (positions_ecef, quats_ecef) into the local frame described by the +To transform global Mesh3D positions and orientations (positions_ecef, quats_ecef) into the local frame described by the first position and orientation from Mesh3D one would do: ``` ecef_from_local = rot_from_quat(quats_ecef[0]) diff --git a/selfdrive/camerad/cameras/camera_qcom2.c b/selfdrive/camerad/cameras/camera_qcom2.c index 75fa803a..060010de 100644 --- a/selfdrive/camerad/cameras/camera_qcom2.c +++ b/selfdrive/camerad/cameras/camera_qcom2.c @@ -261,7 +261,7 @@ void sensors_init(int video0_fd, int sensor_fd, int camera_num) { power->power_settings[2].power_seq_type = 2; // digital power->power_settings[3].power_seq_type = 8; // reset low power = (void*)power + (sizeof(struct cam_cmd_power) + (power->count-1)*sizeof(struct cam_power_settings)); - + unconditional_wait = (void*)power; unconditional_wait->cmd_type = CAMERA_SENSOR_CMD_TYPE_WAIT; unconditional_wait->delay = 5; @@ -424,7 +424,7 @@ void config_isp(struct CameraState *s, int io_mem_handle, int fence, int request 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, - 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0}; + 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0}; memcpy(buf2, tmp, sizeof(tmp)); if (io_mem_handle != 0) { @@ -610,7 +610,7 @@ static void camera_open(CameraState *s, VisionBuf* b) { acquire_dev_cmd.handle_type = CAM_HANDLE_USER_POINTER; acquire_dev_cmd.num_resources = 1; acquire_dev_cmd.resource_hdl = (uint64_t)&isp_resource; - + isp_resource.resource_id = CAM_ISP_RES_ID_PORT; isp_resource.length = sizeof(struct cam_isp_in_port_info) + sizeof(struct cam_isp_out_port_info)*(1-1); isp_resource.handle_type = CAM_HANDLE_USER_POINTER; @@ -643,7 +643,7 @@ static void camera_open(CameraState *s, VisionBuf* b) { in_port_info->test_pattern = 0x2; // 0x3? in_port_info->usage_type = 0x0; - + in_port_info->left_start = 0x0; in_port_info->left_stop = FRAME_WIDTH - 1; in_port_info->left_width = FRAME_WIDTH; @@ -664,10 +664,10 @@ static void camera_open(CameraState *s, VisionBuf* b) { in_port_info->num_out_res = 0x1; in_port_info->data[0] = (struct cam_isp_out_port_info){ - .res_type = CAM_ISP_IFE_OUT_RES_RDI_0, + .res_type = CAM_ISP_IFE_OUT_RES_RDI_0, //.format = CAM_FORMAT_MIPI_RAW_12, .format = CAM_FORMAT_MIPI_RAW_10, - .width = FRAME_WIDTH, + .width = FRAME_WIDTH, .height = FRAME_HEIGHT, .comp_grp_id = 0x0, .split_point = 0x0, .secure_mode = 0x0, }; @@ -700,7 +700,7 @@ static void camera_open(CameraState *s, VisionBuf* b) { CAM_SENSOR_PACKET_OPCODE_SENSOR_CONFIG); sensors_i2c(s, start_reg_array, sizeof(start_reg_array)/sizeof(struct i2c_random_wr_payload), CAM_SENSOR_PACKET_OPCODE_SENSOR_STREAMON); - sensors_i2c(s, stop_reg_array, sizeof(stop_reg_array)/sizeof(struct i2c_random_wr_payload), + sensors_i2c(s, stop_reg_array, sizeof(stop_reg_array)/sizeof(struct i2c_random_wr_payload), CAM_SENSOR_PACKET_OPCODE_SENSOR_STREAMOFF); // config csiphy @@ -817,7 +817,7 @@ void cameras_open(DualCameraState *s, VisionBuf *camera_bufs_rear, VisionBuf *ca s->rear.device_iommu = s->front.device_iommu = s->wide.device_iommu = device_iommu; s->rear.cdm_iommu = s->front.cdm_iommu = s->wide.cdm_iommu = cdm_iommu; - // subscribe + // subscribe LOG("-- Subscribing"); static struct v4l2_event_subscription sub = {0}; sub.type = 0x8000000; diff --git a/selfdrive/camerad/cameras/sensor2_i2c.h b/selfdrive/camerad/cameras/sensor2_i2c.h index 621d2825..7174bb89 100644 --- a/selfdrive/camerad/cameras/sensor2_i2c.h +++ b/selfdrive/camerad/cameras/sensor2_i2c.h @@ -302,8 +302,8 @@ struct i2c_random_wr_payload init_array_ar0231[] = { }; struct i2c_random_wr_payload poke_array_ov7750[] = { - {0x3208, 0x0}, {0x380e, 0x1a}, {0x380f, 0xf0}, {0x3500, 0x0}, {0x3501, 0x0}, {0x3502, 0x10}, {0x350a, 0x0}, {0x350b, 0x10}, {0x3208, 0x10}, {0x3208, 0xa0}, - //{0x3208, 0x0}, {0x380e, 0x1a}, {0x380f, 0xf0}, {0x3500, 0x0}, {0x3501, 0x0}, {0x3502, 0x10}, {0x350a, 0x0}, {0x350b, 0x10}, {0x3208, 0x10}, {0x3208, 0xa0}, + {0x3208, 0x0}, {0x380e, 0x1a}, {0x380f, 0xf0}, {0x3500, 0x0}, {0x3501, 0x0}, {0x3502, 0x10}, {0x350a, 0x0}, {0x350b, 0x10}, {0x3208, 0x10}, {0x3208, 0xa0}, + //{0x3208, 0x0}, {0x380e, 0x1a}, {0x380f, 0xf0}, {0x3500, 0x0}, {0x3501, 0x0}, {0x3502, 0x10}, {0x350a, 0x0}, {0x350b, 0x10}, {0x3208, 0x10}, {0x3208, 0xa0}, }; struct i2c_random_wr_payload preinit_array_ov7750[] = { diff --git a/selfdrive/camerad/imgproc/conv.cl b/selfdrive/camerad/imgproc/conv.cl index f92d3567..a7115ae7 100644 --- a/selfdrive/camerad/imgproc/conv.cl +++ b/selfdrive/camerad/imgproc/conv.cl @@ -3,7 +3,7 @@ // convert input rgb image to single channel then conv __kernel void rgb2gray_conv2d( - const __global uchar * input, + const __global uchar * input, __global short * output, __constant short * filter, __local uchar3 * cached @@ -23,8 +23,8 @@ __kernel void rgb2gray_conv2d( // pad if ( - get_global_id(0) < HALF_FILTER_SIZE || - get_global_id(0) > IMAGE_W - HALF_FILTER_SIZE - 1 || + get_global_id(0) < HALF_FILTER_SIZE || + get_global_id(0) > IMAGE_W - HALF_FILTER_SIZE - 1 || get_global_id(1) < HALF_FILTER_SIZE || get_global_id(1) > IMAGE_H - HALF_FILTER_SIZE - 1 ) @@ -32,11 +32,11 @@ __kernel void rgb2gray_conv2d( barrier(CLK_LOCAL_MEM_FENCE); return; } - else + else { int localColOffset = -1; int globalColOffset = -1; - + // cache extra if ( get_local_id(0) < HALF_FILTER_SIZE ) { @@ -51,7 +51,7 @@ __kernel void rgb2gray_conv2d( { localColOffset = get_local_id(0) + TWICE_HALF_FILTER_SIZE; globalColOffset = HALF_FILTER_SIZE; - + cached[ myLocal + HALF_FILTER_SIZE ].x = input[ my * 3 + HALF_FILTER_SIZE * 3 ]; cached[ myLocal + HALF_FILTER_SIZE ].y = input[ my * 3 + HALF_FILTER_SIZE * 3 + 1]; cached[ myLocal + HALF_FILTER_SIZE ].z = input[ my * 3 + HALF_FILTER_SIZE * 3 + 2]; diff --git a/selfdrive/camerad/imgproc/pool.cl b/selfdrive/camerad/imgproc/pool.cl index 3ba86ae2..d674b5f3 100644 --- a/selfdrive/camerad/imgproc/pool.cl +++ b/selfdrive/camerad/imgproc/pool.cl @@ -1,6 +1,6 @@ // calculate variance in each subregion __kernel void var_pool( - const __global char * input, + const __global char * input, __global ushort * output // should not be larger than 128*128 so uint16 ) { @@ -11,7 +11,7 @@ __kernel void var_pool( float fsum = 0; char mean, max; - + for (int i = 0; i < size; i++) { int x_offset = i % X_PITCH; int y_offset = i / X_PITCH; diff --git a/selfdrive/camerad/transforms/rgb_to_yuv.c b/selfdrive/camerad/transforms/rgb_to_yuv.c index b9e66b36..1a36650b 100644 --- a/selfdrive/camerad/transforms/rgb_to_yuv.c +++ b/selfdrive/camerad/transforms/rgb_to_yuv.c @@ -43,7 +43,7 @@ void rgb_to_yuv_queue(RGBToYUVState* s, cl_command_queue q, cl_mem rgb_cl, cl_me err = clSetKernelArg(s->rgb_to_yuv_krnl, 1, sizeof(cl_mem), &yuv_cl); assert(err == 0); const size_t work_size[2] = { - (size_t)(s->width + (s->width % 4 == 0 ? 0 : (4 - s->width % 4))) / 4, + (size_t)(s->width + (s->width % 4 == 0 ? 0 : (4 - s->width % 4))) / 4, (size_t)(s->height + (s->height % 4 == 0 ? 0 : (4 - s->height % 4))) / 4 }; cl_event event; diff --git a/selfdrive/common/buffering.c b/selfdrive/common/buffering.c index 9cbb1b86..bba2e82a 100644 --- a/selfdrive/common/buffering.c +++ b/selfdrive/common/buffering.c @@ -70,7 +70,7 @@ void tbuffer_dispatch(TBuffer *tb, int idx) { efd_write(tb->efd); pthread_cond_signal(&tb->cv); - pthread_mutex_unlock(&tb->lock); + pthread_mutex_unlock(&tb->lock); } int tbuffer_acquire(TBuffer *tb) { @@ -344,7 +344,7 @@ void pool_push(Pool *s, int idx) { for (int i=0; iqueues[i]; if (!c->inited) continue; - + pthread_mutex_lock(&c->lock); if (((c->head+1) % c->num) == c->tail) { // queue is full. skip for now diff --git a/selfdrive/common/framebuffer.cc b/selfdrive/common/framebuffer.cc index 7bea565d..1d8ccdbd 100644 --- a/selfdrive/common/framebuffer.cc +++ b/selfdrive/common/framebuffer.cc @@ -98,7 +98,7 @@ extern "C" FramebufferState* framebuffer_init( assert(success); printf("egl version %d.%d\n", s->egl_major, s->egl_minor); - + EGLint num_configs; success = eglChooseConfig(s->display, attribs, &s->config, 1, &num_configs); assert(success); diff --git a/selfdrive/locationd/paramsd.cc b/selfdrive/locationd/paramsd.cc index 80eda710..b5fa380c 100644 --- a/selfdrive/locationd/paramsd.cc +++ b/selfdrive/locationd/paramsd.cc @@ -138,7 +138,7 @@ int main(int argc, char *argv[]) { } if (sm.updated("cameraOdometry")){ localizer.handle_log(sm["cameraOdometry"]); - } + } } return 0; } diff --git a/selfdrive/loggerd/frame_logger.h b/selfdrive/loggerd/frame_logger.h index bfc0681b..85ddabaf 100644 --- a/selfdrive/loggerd/frame_logger.h +++ b/selfdrive/loggerd/frame_logger.h @@ -15,7 +15,7 @@ public: int LogFrame(uint64_t ts, const uint8_t *y_ptr, const uint8_t *u_ptr, const uint8_t *v_ptr, int *frame_segment) { std::lock_guard guard(lock); - + if (opening) { Open(next_path); opening = false; diff --git a/selfdrive/loggerd/loggerd.cc b/selfdrive/loggerd/loggerd.cc index b7c7303c..d9c5017f 100644 --- a/selfdrive/loggerd/loggerd.cc +++ b/selfdrive/loggerd/loggerd.cc @@ -729,7 +729,7 @@ int main(int argc, char** argv) { for (auto s : socks){ delete s; } - + delete poller; delete s.ctx; return 0; diff --git a/selfdrive/modeld/modeld.cc b/selfdrive/modeld/modeld.cc index 217654dc..793474e6 100644 --- a/selfdrive/modeld/modeld.cc +++ b/selfdrive/modeld/modeld.cc @@ -44,7 +44,7 @@ void* live_thread(void *arg) { while (!do_exit) { if (sm.update(10) > 0){ - + auto extrinsic_matrix = sm["liveCalibration"].getLiveCalibration().getExtrinsicMatrix(); Eigen::Matrix extrinsic_matrix_eigen; for (int i = 0; i < 4*3; i++){ diff --git a/selfdrive/modeld/thneed/debug/main.cc b/selfdrive/modeld/thneed/debug/main.cc index 07a7d123..b9848705 100644 --- a/selfdrive/modeld/thneed/debug/main.cc +++ b/selfdrive/modeld/thneed/debug/main.cc @@ -180,7 +180,7 @@ if (intercept) { //disassemble((uint32_t *)qcmd.data(), qcmd.size()/4); //queue_cmds.push_back(qcmd); } - + #ifdef DUMP char tmp[0x100]; snprintf(tmp, sizeof(tmp), "/tmp/thneed/run_%d_%d", run_num, ioctl_num++); @@ -515,7 +515,7 @@ cl_mem clCreateImage(cl_context context, cl_mem_flags flags, const cl_image_form assert(image_desc->image_array_size == 0); assert(image_desc->image_slice_pitch == 0); //assert(image_desc->image_width * image_desc->image_height * 2 == image_desc->image_row_pitch); - + image img; img.image_width = image_desc->image_width; img.image_height = image_desc->image_height; @@ -689,7 +689,7 @@ int main(int argc, char* argv[]) { maps[len] = '\0'; fclose(f); printf("%s\n", maps);*/ - + printf("buffers: %lu images: %lu\n", buffers.size(), images.size()); printf("queues: %lu\n", queue_cmds.size()); diff --git a/selfdrive/modeld/thneed/debug/microbenchmark/gemm_image.cl b/selfdrive/modeld/thneed/debug/microbenchmark/gemm_image.cl index 46b6bf6e..f466a8ca 100644 --- a/selfdrive/modeld/thneed/debug/microbenchmark/gemm_image.cl +++ b/selfdrive/modeld/thneed/debug/microbenchmark/gemm_image.cl @@ -14,8 +14,8 @@ #pragma OPENCL EXTENSION cl_khr_fp16 : enable __kernel void gemm(const int M, const int N, const int K, - read_only image2d_t A, - read_only image2d_t B, + read_only image2d_t A, + read_only image2d_t B, write_only image2d_t C) { const sampler_t smp = CLK_NORMALIZED_COORDS_FALSE | diff --git a/selfdrive/modeld/thneed/debug/microbenchmark/go.c b/selfdrive/modeld/thneed/debug/microbenchmark/go.c index 56350856..18b91a6c 100644 --- a/selfdrive/modeld/thneed/debug/microbenchmark/go.c +++ b/selfdrive/modeld/thneed/debug/microbenchmark/go.c @@ -128,7 +128,7 @@ int main(int argc, char *argv[]) { M = N = K = 1024; //M = 128; K = 2112; N = 352; - + cl_kernel kern = clCreateKernel(prog, "gemm", &err); assert(err == 0); printf("creating kernel %p\n", kern); @@ -255,7 +255,7 @@ int main(int argc, char *argv[]) { clSetKernelArg(kern, 20, sizeof(n), &n); clSetKernelArg(kern, 21, sizeof(n), &n); v = 16; clSetKernelArg(kern, 22, sizeof(v), &v); - + size_t global_work_size[3] = {88, 4, 8}; size_t local_work_size[3] = {4, 4, 8}; #endif diff --git a/selfdrive/ui/text/text.c b/selfdrive/ui/text/text.c index cd910cc8..6a2b6c75 100644 --- a/selfdrive/ui/text/text.c +++ b/selfdrive/ui/text/text.c @@ -81,7 +81,7 @@ assert(font >= 0); float lineh; nvgTextMetrics(vg, NULL, NULL, &lineh); - + // nvgTextBox strips leading whitespace. We have to reimplement char * next = strtok(text, "\n"); while (next != NULL){ diff --git a/tools/lib/vidindex/vidindex.c b/tools/lib/vidindex/vidindex.c index a8d53d94..4857c60d 100644 --- a/tools/lib/vidindex/vidindex.c +++ b/tools/lib/vidindex/vidindex.c @@ -18,7 +18,7 @@ static uint32_t read24be(const uint8_t* ptr) { } static void write32le(FILE *of, uint32_t v) { uint8_t va[4] = { - v & 0xff, (v >> 8) & 0xff, (v >> 16) & 0xff, (v >> 24) & 0xff + v & 0xff, (v >> 8) & 0xff, (v >> 16) & 0xff, (v >> 24) & 0xff }; fwrite(va, 1, sizeof(va), of); } @@ -135,7 +135,7 @@ static void hevc_index(const uint8_t *data, size_t file_size, FILE *of_prefix, F bs_get(&bs, 1); } uint32_t slice_type = bs_ue(&bs); - + // write the index write32le(of_index, slice_type); write32le(of_index, ptr - data); @@ -244,7 +244,7 @@ static void h264_index(const uint8_t *data, size_t file_size, FILE *of_prefix, F uint32_t pic_parameter_set_id = bs_ue(&bs); uint32_t frame_num = bs_get(&bs, sps_log2_max_frame_num_minus4+4); - + if (first_mb_in_slice == 0) { write32le(of_index, slice_type); write32le(of_index, ptr - data); diff --git a/tools/nui/FileReader.cpp b/tools/nui/FileReader.cpp index d52305b1..fe360da9 100644 --- a/tools/nui/FileReader.cpp +++ b/tools/nui/FileReader.cpp @@ -71,7 +71,7 @@ LogReader::LogReader(const QString& file, Events *events_, QReadWriteLock* event while (1) { mergeEvents(cdled.get()); } - }); + }); } void LogReader::mergeEvents(int dled) { diff --git a/tools/nui/Unlogger.cpp b/tools/nui/Unlogger.cpp index c217a067..d48c607f 100644 --- a/tools/nui/Unlogger.cpp +++ b/tools/nui/Unlogger.cpp @@ -4,7 +4,7 @@ #include #include -// include the dynamic struct +// include the dynamic struct #include "cereal/gen/cpp/car.capnp.c++" #include "cereal/gen/cpp/log.capnp.c++" @@ -24,7 +24,7 @@ static inline uint64_t nanos_since_boot() { } -Unlogger::Unlogger(Events *events_, QReadWriteLock* events_lock_, QMap *frs_, int seek) +Unlogger::Unlogger(Events *events_, QReadWriteLock* events_lock_, QMap *frs_, int seek) : events(events_), events_lock(events_lock_), frs(frs_) { ctx = Context::create(); YAML::Node service_list = YAML::LoadFile("../../cereal/service_list.yaml"); diff --git a/tools/nui/main.cpp b/tools/nui/main.cpp index c0527554..46dab5df 100644 --- a/tools/nui/main.cpp +++ b/tools/nui/main.cpp @@ -44,7 +44,7 @@ class Window : public QWidget { QMap lrs; QMap frs; - + // cache the bar QPixmap *px = NULL; @@ -72,7 +72,7 @@ Window::Window(QString route_, int seek, int use_api_) : route(route_), use_api( file.open(QIODevice::ReadOnly | QIODevice::Text); settings = file.readAll(); file.close(); - + QJsonDocument sd = QJsonDocument::fromJson(settings.toUtf8()); qWarning() << sd.isNull(); // <- print false :) QJsonObject sett2 = sd.object(); @@ -97,7 +97,7 @@ bool Window::addSegment(int i) { lrs.insert(i, new LogReader(fn, &events, &events_lock, &unlogger->eidx)); } else { QString log_fn = this->log_paths.at(i).toString(); - lrs.insert(i, new LogReader(log_fn, &events, &events_lock, &unlogger->eidx)); + lrs.insert(i, new LogReader(log_fn, &events, &events_lock, &unlogger->eidx)); } @@ -114,8 +114,8 @@ bool Window::addSegment(int i) { QString camera_fn = this->camera_paths.at(i).toString(); frs.insert(i, new FrameReader(qPrintable(camera_fn))); } - - + + return true; } return false; @@ -193,9 +193,9 @@ void Window::paintEvent(QPaintEvent *event) { tt.drawLine(lt, 300-lvv, rt, 300-vv); if (enabled) { - tt.setPen(Qt::green); + tt.setPen(Qt::green); } else { - tt.setPen(Qt::blue); + tt.setPen(Qt::blue); } tt.drawLine(rt, 300, rt, 600); @@ -237,7 +237,7 @@ int main(int argc, char *argv[]) { QApplication app(argc, argv); QString route(argv[1]); - + int use_api = QString::compare(QString("use_api"), route, Qt::CaseInsensitive) == 0; int seek = QString(argv[2]).toInt(); printf("seek: %d\n", seek); @@ -251,7 +251,7 @@ int main(int argc, char *argv[]) { } Window window(route, seek, use_api); - + window.resize(1920, 800); window.setWindowTitle("nui unlogger"); window.show(); diff --git a/tools/nui/nui b/tools/nui/nui index 35d3cfa6..52148021 100755 --- a/tools/nui/nui +++ b/tools/nui/nui @@ -9,4 +9,3 @@ if [ $# -gt 0 ]; then else echo "Please Enter a Route" fi - \ No newline at end of file diff --git a/tools/sim/README.md b/tools/sim/README.md index 8277ab1f..4b64d4a8 100644 --- a/tools/sim/README.md +++ b/tools/sim/README.md @@ -10,24 +10,24 @@ git clone https://github.com/commaai/openpilot.git # Add export PYTHONPATH=$HOME/openpilot to your bashrc # Have a working tensorflow+keras in python3.7.3 (with [packages] in openpilot/Pipfile) ``` -## Install (in tab 1) +## Install (in tab 1) ``` cd ~/openpilot/tools/sim ./start_carla.sh # install CARLA 0.9.7 and start the server ``` -## openpilot (in tab 2) +## openpilot (in tab 2) ``` cd ~/openpilot/selfdrive/ PASSIVE=0 NOBOARD=1 ./manager.py ``` -## bridge (in tab 3) +## bridge (in tab 3) ``` # links carla to openpilot, will "start the car" according to manager cd ~/openpilot/tools/sim ./bridge.py ``` -## Controls -Now you can control the simulator with the keys: +## Controls +Now you can control the simulator with the keys: 1: Cruise up 5 mph diff --git a/tools/sim/start_carla.sh b/tools/sim/start_carla.sh index 42c956c2..cc5e961b 100755 --- a/tools/sim/start_carla.sh +++ b/tools/sim/start_carla.sh @@ -15,4 +15,4 @@ if [ ! -d carla ]; then fi cd carla -./CarlaUE4.sh +./CarlaUE4.sh diff --git a/tools/webcam/README.md b/tools/webcam/README.md index f03f811b..e5589fbc 100644 --- a/tools/webcam/README.md +++ b/tools/webcam/README.md @@ -1,49 +1,49 @@ Run openpilot with webcam on PC/laptop ===================== -What's needed: -- Ubuntu 16.04 -- Python 3.7.3 -- GPU (recommended) -- Two USB webcams, at least 720p and 78 degrees FOV (e.g. Logitech C920/C615) -- [Car harness](https://comma.ai/shop/products/comma-car-harness) w/ black panda (or the outdated grey panda/giraffe combo) to connect to your car -- [Panda paw](https://comma.ai/shop/products/panda-paw) (or USB-A to USB-A cable) to connect panda to your computer -- Tape, Charger, ... -That's it! +What's needed: +- Ubuntu 16.04 +- Python 3.7.3 +- GPU (recommended) +- Two USB webcams, at least 720p and 78 degrees FOV (e.g. Logitech C920/C615) +- [Car harness](https://comma.ai/shop/products/comma-car-harness) w/ black panda (or the outdated grey panda/giraffe combo) to connect to your car +- [Panda paw](https://comma.ai/shop/products/panda-paw) (or USB-A to USB-A cable) to connect panda to your computer +- Tape, Charger, ... +That's it! -## Clone openpilot and install the requirements +## Clone openpilot and install the requirements ``` -cd ~ -git clone https://github.com/commaai/openpilot.git +cd ~ +git clone https://github.com/commaai/openpilot.git ``` -- Follow [this readme](https://github.com/commaai/openpilot/tree/master/tools) to install the requirements -- Add line "export PYTHONPATH=$HOME/openpilot" to your ~/.bashrc -- You also need to install tensorflow 2.2 and nvidia drivers: nvidia-xxx/cuda10.0/cudnn7.6.5 -- Install [OpenCL Driver](http://registrationcenter-download.intel.com/akdlm/irc_nas/vcp/15532/l_opencl_p_18.1.0.015.tgz) -- (Note: the code assumes cl platforms order to be 0.GPU/1.CPU when running clinfo; if reverse, change the -1 to -2 in selfdrive/modeld/modeld.cc#L130; helping us refactor this mess is encouraged) -- Install [OpenCV4](https://www.pyimagesearch.com/2018/08/15/how-to-install-opencv-4-on-ubuntu/) (ignore the Python part) +- Follow [this readme](https://github.com/commaai/openpilot/tree/master/tools) to install the requirements +- Add line "export PYTHONPATH=$HOME/openpilot" to your ~/.bashrc +- You also need to install tensorflow 2.2 and nvidia drivers: nvidia-xxx/cuda10.0/cudnn7.6.5 +- Install [OpenCL Driver](http://registrationcenter-download.intel.com/akdlm/irc_nas/vcp/15532/l_opencl_p_18.1.0.015.tgz) +- (Note: the code assumes cl platforms order to be 0.GPU/1.CPU when running clinfo; if reverse, change the -1 to -2 in selfdrive/modeld/modeld.cc#L130; helping us refactor this mess is encouraged) +- Install [OpenCV4](https://www.pyimagesearch.com/2018/08/15/how-to-install-opencv-4-on-ubuntu/) (ignore the Python part) -## Build openpilot for webcam +## Build openpilot for webcam ``` -cd ~/openpilot +cd ~/openpilot ``` -- check out selfdrive/camerad/cameras/camera_webcam.cc line72&146 before building if any camera is upside down +- check out selfdrive/camerad/cameras/camera_webcam.cc line72&146 before building if any camera is upside down ``` -scons use_webcam=1 -touch prebuilt +scons use_webcam=1 +touch prebuilt ``` -## Connect the hardwares -- Connect the road facing camera first, then the driver facing camera -- (default indexes are 1 and 2; can be modified in selfdrive/camerad/cameras/camera_webcam.cc) -- Connect your computer to panda +## Connect the hardwares +- Connect the road facing camera first, then the driver facing camera +- (default indexes are 1 and 2; can be modified in selfdrive/camerad/cameras/camera_webcam.cc) +- Connect your computer to panda -## GO +## GO ``` -cd ~/openpilot/tools/webcam -./accept_terms.py # accept the user terms so that thermald can detect the car started -cd ~/openpilot/selfdrive -PASSIVE=0 NOSENSOR=1 WEBCAM=1 ./manager.py +cd ~/openpilot/tools/webcam +./accept_terms.py # accept the user terms so that thermald can detect the car started +cd ~/openpilot/selfdrive +PASSIVE=0 NOSENSOR=1 WEBCAM=1 ./manager.py ``` -- Start the car, then the UI should show the road webcam's view -- Adjust and secure the webcams (you can run tools/webcam/front_mount_helper.py to help mount the driver camera) -- Finish calibration and engage! +- Start the car, then the UI should show the road webcam's view +- Adjust and secure the webcams (you can run tools/webcam/front_mount_helper.py to help mount the driver camera) +- Finish calibration and engage!