monado: Apply clang-tidy fixes to most of the codebase.

All at least visually inspected, some revised from the auto-fixit
This commit is contained in:
Ryan Pavlik 2022-04-12 16:20:11 -05:00
parent f705683957
commit 3e6ec47296
95 changed files with 447 additions and 349 deletions

View file

@ -1,24 +1,30 @@
---
# SPDX-License-Identifier: CC0-1.0
# SPDX-FileCopyrightText: 2018-2020 Collabora, Ltd. and the Monado contributors
# Ideally we'd turn back on a few of these that are disabled near the end
Checks: 'clang-diagnostic-*,
clang-analyzer-*,
performance-*,
bugprone-*,
cert-*,
readability-*,
misc-*,
-modernize-*,
-clang-analyzer-security.insecureAPI.strcpy,
-bugprone-macro-parentheses,
-readability-braces-around-statements,
-misc-unused-parameters,
-readability-implicit-bool-conversion,
-clang-diagnostic-missing-field-initializers,
-clang-diagnostic-missing-braces,
-readability-uppercase-literal-suffix,
-misc-non-private-member-variables-in-classes'
# SPDX-FileCopyrightText: 2018-2022, Collabora, Ltd. and the Monado contributors
# Ideally we'd turn back on some of these that are disabled.
# Things on the same line are synonyms
Checks: |
clang-diagnostic-*,
clang-analyzer-*,
performance-*,
bugprone-*,
cert-*,
readability-*,
misc-*,
-modernize-*,
-misc-static-assert,
-bugprone-macro-parentheses,
-bugprone-reserved-identifier,-cert-dcl37-c,-cert-dcl51-cpp,
-clang-analyzer-security.insecureAPI.DeprecatedOrUnsafeBufferHandling,
-clang-analyzer-security.insecureAPI.strcpy,
-clang-diagnostic-missing-braces,
-clang-diagnostic-missing-field-initializers,
-misc-non-private-member-variables-in-classes,
-misc-unused-parameters,
-readability-braces-around-statements,
-readability-implicit-bool-conversion,
-readability-redundant-access-specifiers,
-readability-uppercase-literal-suffix,
WarningsAsErrors: ''
HeaderFilterRegex: 'src/xrt/.*'
AnalyzeTemporaryDtors: false

View file

@ -20,7 +20,7 @@ struct gstreamer_pipeline;
void
gstreamer_sink_send_eos(struct gstreamer_sink *gp);
gstreamer_sink_send_eos(struct gstreamer_sink *gs);
uint64_t
gstreamer_sink_get_timestamp_offset(struct gstreamer_sink *gs);

View file

@ -327,7 +327,7 @@ math_quat_ln(const struct xrt_quat *quat, struct xrt_vec3 *out_axis_angle);
* @ingroup aux_math
*/
void
math_quat_rotate_derivative(const struct xrt_quat *rot, const struct xrt_vec3 *deriv, struct xrt_vec3 *result);
math_quat_rotate_derivative(const struct xrt_quat *quat, const struct xrt_vec3 *deriv, struct xrt_vec3 *result);
/*!

View file

@ -127,7 +127,9 @@ m_ff_vec3_f32_filter(struct m_ff_vec3_f32 *ff, uint64_t start_ns, uint64_t stop_
size_t num_sampled = 0;
size_t count = 0;
// Use double precision internally.
double x = 0, y = 0, z = 0;
double x = 0;
double y = 0;
double z = 0;
// Error, skip averaging.
if (start_ns > stop_ns) {

View file

@ -125,7 +125,7 @@ filter_one_euro_compute_alpha(const struct m_filter_one_euro_base *f, double dt,
void
m_filter_euro_f32_init(struct m_filter_euro_f32 *f, double fc_min, double beta, double fc_min_d)
m_filter_euro_f32_init(struct m_filter_euro_f32 *f, double fc_min, double fc_min_d, double beta)
{
filter_one_euro_init(&f->base, fc_min, beta, fc_min_d);
}

View file

@ -102,12 +102,12 @@ struct m_filter_euro_quat
};
void
m_filter_euro_f32_init(struct m_filter_euro_f32 *f, double fc_min, double beta, double fc_min_d);
m_filter_euro_f32_init(struct m_filter_euro_f32 *f, double fc_min, double fc_min_d, double beta);
void
m_filter_euro_f32_run(struct m_filter_euro_f32 *f, uint64_t ts, const float *in_y, float *out_y);
void
m_filter_euro_vec2_init(struct m_filter_euro_vec2 *f, double fc_min, double beta, double fc_min_d);
m_filter_euro_vec2_init(struct m_filter_euro_vec2 *f, double fc_min, double fc_min_d, double beta);
void
m_filter_euro_vec2_run(struct m_filter_euro_vec2 *f, uint64_t ts, const struct xrt_vec2 *in_y, struct xrt_vec2 *out_y);
void

View file

@ -117,8 +117,10 @@ gravity_correction(struct m_imu_3dof *f,
return;
}
const float gravity_tolerance = .9f, gyro_tolerance = .1f;
const float min_tilt_error = 0.05f, max_tilt_error = 0.01f;
const float gravity_tolerance = .9f;
const float gyro_tolerance = .1f;
const float min_tilt_error = 0.05f;
const float max_tilt_error = 0.01f;
/*
* If the device is within tolerance levels, count this
@ -196,7 +198,8 @@ gravity_correction(struct m_imu_3dof *f,
f->grav.error_angle += correction_radians;
// Perform the correction.
struct xrt_quat corr_quat, old_orient;
struct xrt_quat corr_quat;
struct xrt_quat old_orient;
math_quat_from_angle_vector(correction_radians, &f->grav.error_axis, &corr_quat);
old_orient = f->rot;
math_quat_rotate(&corr_quat, &old_orient, &f->rot);

View file

@ -86,7 +86,7 @@ m_imu_3dof_add_vars(struct m_imu_3dof *f, void *root, const char *prefix);
void
m_imu_3dof_update(struct m_imu_3dof *f,
uint64_t timepoint_ns,
uint64_t timestamp_ns,
const struct xrt_vec3 *accel,
const struct xrt_vec3 *gyro);

View file

@ -64,8 +64,10 @@ m_imu_pre_filter_data(struct m_imu_pre_filter *imu,
struct xrt_vec3 *out_accel,
struct xrt_vec3 *out_gyro)
{
struct m_imu_pre_filter_part fa, fg;
struct xrt_vec3 a, g;
struct m_imu_pre_filter_part fa;
struct m_imu_pre_filter_part fg;
struct xrt_vec3 a;
struct xrt_vec3 g;
struct xrt_matrix_3x3 m;
fa = imu->accel;

View file

@ -60,10 +60,9 @@ step(struct m_permutator *mp)
mp->indices[mp->i]++;
mp->i = 0;
return true;
} else {
mp->indices[mp->i] = 0;
mp->i++;
}
mp->indices[mp->i] = 0;
mp->i++;
}
return false;
@ -83,7 +82,8 @@ m_permutator_step(struct m_permutator *mp, uint32_t *out_elements, uint32_t num_
setup(mp, num_elements);
copy(mp, out_elements);
return true;
} else if (step(mp)) {
}
if (step(mp)) {
copy(mp, out_elements);
return true;

View file

@ -54,7 +54,9 @@ m_relation_history_create(struct m_relation_history **rh);
* @public @memberof m_relation_history
*/
bool
m_relation_history_push(struct m_relation_history *rh, struct xrt_space_relation const *in_relation, uint64_t ts);
m_relation_history_push(struct m_relation_history *rh,
struct xrt_space_relation const *in_relation,
uint64_t timestamp);
/*!
* @brief Interpolates or extrapolates to the desired timestamp.
@ -65,7 +67,9 @@ m_relation_history_push(struct m_relation_history *rh, struct xrt_space_relation
* @public @memberof m_relation_history
*/
enum m_relation_history_result
m_relation_history_get(struct m_relation_history *rh, uint64_t at_time_ns, struct xrt_space_relation *out_relation);
m_relation_history_get(struct m_relation_history *rh,
uint64_t at_timestamp_ns,
struct xrt_space_relation *out_relation);
/*!
* @brief Get the latest report in the buffer, if any.

View file

@ -113,9 +113,8 @@ m_relation_chain_reserve(struct xrt_relation_chain *xrc)
{
if (xrc->step_count < XRT_RELATION_CHAIN_CAPACITY) {
return &xrc->steps[xrc->step_count++];
} else {
return NULL;
}
return NULL;
}
/*!

View file

@ -84,7 +84,7 @@ os_ble_notify_open(const char *dev_uuid, const char *char_uuid, struct os_ble_de
* @ingroup aux_os
*/
int
os_ble_broadcast_write_value(const char *dev_uuid, const char *char_uuid, uint8_t value);
os_ble_broadcast_write_value(const char *service_uuid, const char *char_uuid, uint8_t value);
#endif

View file

@ -72,7 +72,8 @@ add_single_byte_array(DBusMessage *msg, uint8_t value)
{
// Create an array of bytes.
const char *container_signature = "y"; // dbus type signature string
DBusMessageIter iter, array;
DBusMessageIter iter;
DBusMessageIter array;
// attach it to our dbus message
dbus_message_iter_init_append(msg, &iter);
@ -86,7 +87,8 @@ add_empty_dict_sv(DBusMessage *msg)
{
// Create an empty array of string variant dicts.
const char *container_signature = "{sv}"; // dbus type signature string
DBusMessageIter iter, options;
DBusMessageIter iter;
DBusMessageIter options;
// attach it to our dbus message
dbus_message_iter_init_append(msg, &iter);
@ -521,7 +523,8 @@ dbus_has_name(DBusConnection *conn, const char *name)
static int
device_has_uuid(const DBusMessageIter *dict, const char *uuid, const char **out_path_str)
{
DBusMessageIter iface_elm, first_elm;
DBusMessageIter iface_elm;
DBusMessageIter first_elm;
const char *iface_str;
const char *path_str;
@ -616,7 +619,8 @@ gatt_iface_get_uuid(const DBusMessageIter *iface_elm, const char **out_str)
static int
gatt_char_has_uuid_and_notify(const DBusMessageIter *dict, const char *uuid, const char **out_path_str)
{
DBusMessageIter first_elm, iface_elm;
DBusMessageIter first_elm;
DBusMessageIter iface_elm;
const char *iface_str;
const char *path_str;
const char *uuid_str;
@ -753,7 +757,8 @@ ble_connect(struct ble_conn_helper *bch, const char *dbus_address)
DBusMessage *msg = NULL;
DBusMessageIter args;
char *response = NULL;
int ret, type;
int ret;
int type;
I(bch, "Connecting '%s'", dbus_address);
@ -794,7 +799,8 @@ ble_connect(struct ble_conn_helper *bch, const char *dbus_address)
static int
ble_connect_all_devices_with_service_uuid(struct ble_conn_helper *bch, const char *service_uuid)
{
DBusMessageIter args, first_elm;
DBusMessageIter args;
DBusMessageIter first_elm;
DBusMessage *msg = NULL;
int ret = ble_get_managed_objects(bch, &msg);
@ -833,7 +839,8 @@ ble_write_value(struct ble_conn_helper *bch, const char *dbus_address, uint8_t v
DBusMessage *msg = NULL;
DBusMessageIter args;
char *response = NULL;
int ret, type;
int ret;
int type;
msg = dbus_message_new_method_call("org.bluez", // target for the method call
dbus_address, // object to call on
@ -877,7 +884,8 @@ static ssize_t
get_path_to_notify_char(
struct ble_conn_helper *bch, const char *dev_uuid, const char *char_uuid, char *output, size_t output_len)
{
DBusMessageIter args, first_elm;
DBusMessageIter args;
DBusMessageIter first_elm;
DBusMessage *msg;
int ret = ble_get_managed_objects(bch, &msg);
@ -1078,7 +1086,8 @@ int
os_ble_broadcast_write_value(const char *service_uuid, const char *char_uuid, uint8_t value)
{
struct ble_conn_helper bch = {0};
DBusMessageIter args, first_elm;
DBusMessageIter args;
DBusMessageIter first_elm;
DBusMessage *msg = NULL;
int ret = 0;

View file

@ -1390,7 +1390,7 @@ t_calibration_stereo_create(struct xrt_frame_context *xfctx,
//! Helper for NormalizedCoordsCache constructors
static inline std::vector<cv::Vec2f>
generateInputCoordsAndReserveOutputCoords(cv::Size size, std::vector<cv::Vec2f> &outputCoords)
generateInputCoordsAndReserveOutputCoords(const cv::Size &size, std::vector<cv::Vec2f> &outputCoords)
{
std::vector<cv::Vec2f> inputCoords;
@ -1408,7 +1408,7 @@ generateInputCoordsAndReserveOutputCoords(cv::Size size, std::vector<cv::Vec2f>
//! Helper for NormalizedCoordsCache constructors
static inline void
populateCacheMats(cv::Size size,
populateCacheMats(const cv::Size &size,
const std::vector<cv::Vec2f> &inputCoords,
const std::vector<cv::Vec2f> &outputCoords,
cv::Mat_<float> &cacheX,

View file

@ -99,7 +99,7 @@ t_debug_hsv_filter_break_apart(struct xrt_frame_node *node)
extern "C" void
t_debug_hsv_filter_destroy(struct xrt_frame_node *node)
{
auto d = container_of(node, DebugHSVFilter, node);
auto *d = container_of(node, DebugHSVFilter, node);
delete d;
}

View file

@ -79,7 +79,7 @@ process_frame_yuv(class DebugHSVPicker &d, struct xrt_frame *xf)
{
for (uint32_t y = 0; y < xf->height; y++) {
uint8_t *src = (uint8_t *)xf->data + y * xf->stride;
auto hsv = d.debug.hsv.ptr<uint8_t>(y);
auto *hsv = d.debug.hsv.ptr<uint8_t>(y);
for (uint32_t x = 0; x < xf->width; x++) {
uint8_t y = src[0];
uint8_t cb = src[1];
@ -106,7 +106,7 @@ process_frame_yuyv(class DebugHSVPicker &d, struct xrt_frame *xf)
{
for (uint32_t y = 0; y < xf->height; y++) {
uint8_t *src = (uint8_t *)xf->data + y * xf->stride;
auto hsv = d.debug.hsv.ptr<uint8_t>(y);
auto *hsv = d.debug.hsv.ptr<uint8_t>(y);
for (uint32_t x = 0; x < xf->width; x += 2) {
uint8_t y1 = src[0];
uint8_t cb = src[1];
@ -211,7 +211,7 @@ t_debug_hsv_picker_break_apart(struct xrt_frame_node *node)
extern "C" void
t_debug_hsv_picker_destroy(struct xrt_frame_node *node)
{
auto d = container_of(node, DebugHSVPicker, node);
auto *d = container_of(node, DebugHSVPicker, node);
delete d;
}

View file

@ -107,9 +107,9 @@ process_frame(DebugHSVViewer &d, struct xrt_frame *xf)
for (uint32_t yp = 0; yp < SIZE; yp++) {
for (int chan = 0; chan < NUM_CHAN; chan++) {
auto hsv_cap = bgr.ptr<uint8_t>(yp + SIZE * chan);
auto hsv_opt = bgr.ptr<uint8_t>(yp + SIZE * chan) + 256 * 3;
auto hsv_diff = bgr.ptr<uint8_t>(yp + SIZE * chan) + 512 * 3;
auto *hsv_cap = bgr.ptr<uint8_t>(yp + SIZE * chan);
auto *hsv_opt = bgr.ptr<uint8_t>(yp + SIZE * chan) + 256 * 3;
auto *hsv_diff = bgr.ptr<uint8_t>(yp + SIZE * chan) + 512 * 3;
int mask = 1 << chan;
for (uint32_t xp = 0; xp < SIZE; xp++) {
@ -160,7 +160,7 @@ t_debug_hsv_viewer_break_apart(struct xrt_frame_node *node)
extern "C" void
t_debug_hsv_viewer_destroy(struct xrt_frame_node *node)
{
auto d = container_of(node, DebugHSVViewer, node);
auto *d = container_of(node, DebugHSVViewer, node);
delete d;
}

View file

@ -79,7 +79,7 @@ FrameMat::FrameMat()
*/
void
FrameMat::wrapR8G8B8(cv::Mat mat, xrt_frame **fm_out, const Params /*&&?*/ params)
FrameMat::wrapR8G8B8(const cv::Mat &mat, xrt_frame **fm_out, const Params /*&&?*/ params)
{
assert(mat.channels() == 3);
assert(mat.type() == CV_8UC3);
@ -96,7 +96,7 @@ FrameMat::wrapR8G8B8(cv::Mat mat, xrt_frame **fm_out, const Params /*&&?*/ param
}
void
FrameMat::wrapL8(cv::Mat mat, xrt_frame **fm_out, const Params /*&&?*/ params)
FrameMat::wrapL8(const cv::Mat &mat, xrt_frame **fm_out, const Params /*&&?*/ params)
{
assert(mat.channels() == 1);
assert(mat.type() == CV_8UC1);

View file

@ -29,7 +29,7 @@ public:
};
public:
// Exposed to the C api.
struct xrt_frame frame = {};
@ -37,7 +37,7 @@ public:
cv::Mat matrix = cv::Mat();
public:
/*!
* Only public due to C needed to destroy it.
*/
@ -50,7 +50,7 @@ public:
* its reference count decremented so make sure it's a valid pointer.
*/
static void
wrapR8G8B8(cv::Mat mat, xrt_frame **xf_ptr, const Params params = {});
wrapR8G8B8(const cv::Mat &mat, xrt_frame **fm_out, Params params = {});
/*!
* Wraps the given cv::Mat assuming it's a 8bit format matrix.
@ -59,7 +59,7 @@ public:
* its reference count decremented so make sure it's a valid pointer.
*/
static void
wrapL8(cv::Mat mat, xrt_frame **xf_ptr, const Params params = {});
wrapL8(const cv::Mat &mat, xrt_frame **fm_out, Params params = {});
private:

View file

@ -28,7 +28,7 @@ public:
AlwaysSingle,
};
public:
Kind kind = AllAvailable;
struct u_sink_debug usd = {};
struct xrt_frame *frame = {};
@ -36,7 +36,7 @@ public:
cv::Mat rgb[2] = {};
public:
HelperDebugSink(Kind kind)
{
this->kind = kind;
@ -60,7 +60,10 @@ public:
// But what about second breakfast?
bool second_view = false;
int rows, cols, width, height;
int rows;
int cols;
int width;
int height;
cols = xf->width;
rows = xf->height;

View file

@ -295,7 +295,7 @@ t_hand_node_break_apart(struct xrt_frame_node *node)
extern "C" void
t_hand_node_destroy(struct xrt_frame_node *node)
{
auto t_ptr = container_of(node, TrackerHand, node);
auto *t_ptr = container_of(node, TrackerHand, node);
os_thread_helper_destroy(&t_ptr->oth);
// Tidy variable setup.

View file

@ -215,7 +215,7 @@ make_lowest_score_finder(FunctionType scoreFunctor)
//! Convert our 2d point + disparities into 3d points.
static cv::Point3f
world_point_from_blobs(cv::Point2f left, cv::Point2f right, const cv::Matx44d &disparity_to_depth)
world_point_from_blobs(const cv::Point2f &left, const cv::Point2f &right, const cv::Matx44d &disparity_to_depth)
{
float disp = left.x - right.x;
cv::Vec4d xydw(left.x, left.y, disp, 1.0f);
@ -278,7 +278,7 @@ process(TrackerPSMV &t, struct xrt_frame *xf)
do_view(t, t.view[1], r_grey, t.debug.rgb[1]);
cv::Point3f last_point(t.tracked_object_position.x, t.tracked_object_position.y, t.tracked_object_position.z);
auto nearest_world = make_lowest_score_finder<cv::Point3f>([&](cv::Point3f world_point) {
auto nearest_world = make_lowest_score_finder<cv::Point3f>([&](const cv::Point3f &world_point) {
//! @todo don't really need the square root to be done here.
return cv::norm(world_point - last_point);
});
@ -289,8 +289,8 @@ process(TrackerPSMV &t, struct xrt_frame *xf)
for (const cv::KeyPoint &l_keypoint : t.view[0].keypoints) {
cv::Point2f l_blob = l_keypoint.pt;
auto nearest_blob =
make_lowest_score_finder<cv::Point2f>([&](cv::Point2f r_blob) { return l_blob.x - r_blob.x; });
auto nearest_blob = make_lowest_score_finder<cv::Point2f>(
[&](const cv::Point2f &r_blob) { return l_blob.x - r_blob.x; });
for (const cv::KeyPoint &r_keypoint : t.view[1].keypoints) {
cv::Point2f r_blob = r_keypoint.pt;
@ -507,7 +507,7 @@ t_psmv_node_break_apart(struct xrt_frame_node *node)
extern "C" void
t_psmv_node_destroy(struct xrt_frame_node *node)
{
auto t_ptr = container_of(node, TrackerPSMV, node);
auto *t_ptr = container_of(node, TrackerPSMV, node);
os_thread_helper_destroy(&t_ptr->oth);
// Tidy variable setup.

View file

@ -314,7 +314,7 @@ dist_3d(Eigen::Vector4f a, Eigen::Vector4f b)
}
static float
dist_3d_cv(cv::Point3f a, cv::Point3f b)
dist_3d_cv(const cv::Point3f &a, const cv::Point3f &b)
{
return sqrt((a.x - b.x) * (a.x - b.x) + (a.y - b.y) * (a.y - b.y) + (a.z - b.z) * (a.z - b.z));
}
@ -508,7 +508,7 @@ static void
remove_outliers(std::vector<blob_point_t> *orig_points, std::vector<blob_point_t> *pruned_points, float outlier_thresh)
{
if (orig_points->size() == 0) {
if (orig_points->empty()) {
return;
}
@ -523,7 +523,7 @@ remove_outliers(std::vector<blob_point_t> *orig_points, std::vector<blob_point_t
temp_points.push_back(orig_points->at(i));
}
}
if (temp_points.size() == 0) {
if (temp_points.empty()) {
return;
}
@ -620,12 +620,12 @@ merge_close_points(std::vector<blob_point_t> *orig_points, std::vector<blob_poin
static void
match_triangles(Eigen::Matrix4f *t1_mat,
Eigen::Matrix4f *t1_to_t2_mat,
Eigen::Vector4f t1_a,
Eigen::Vector4f t1_b,
Eigen::Vector4f t1_c,
Eigen::Vector4f t2_a,
Eigen::Vector4f t2_b,
Eigen::Vector4f t2_c)
const Eigen::Vector4f &t1_a,
const Eigen::Vector4f &t1_b,
const Eigen::Vector4f &t1_c,
const Eigen::Vector4f &t2_a,
const Eigen::Vector4f &t2_b,
const Eigen::Vector4f &t2_c)
{
// given 3 vertices in 'model space', and a corresponding 3 vertices
// in 'world space', compute the transformation matrix to map one
@ -834,7 +834,7 @@ solve_with_imu(TrackerPSVR &t,
proximity_data.push_back(p);
}
if (proximity_data.size() > 0) {
if (!proximity_data.empty()) {
// use the IMU rotation and the measured points in
// world space to compute a transform from model to world space.
@ -899,7 +899,7 @@ disambiguate(TrackerPSVR &t,
Eigen::Matrix4f imu_solved_pose =
solve_with_imu(t, measured_points, last_measurement, solved, PSVR_SEARCH_RADIUS);
if (measured_points->size() < PSVR_OPTICAL_SOLVE_THRESH && last_measurement->size() > 0) {
if (measured_points->size() < PSVR_OPTICAL_SOLVE_THRESH && !last_measurement->empty()) {
return imu_solved_pose;
}
@ -998,7 +998,10 @@ disambiguate(TrackerPSVR &t,
float prev_diff = last_diff(t, &meas_solved, &t.last_vertices);
float imu_diff = last_diff(t, &meas_solved, solved);
Eigen::Vector4f tl_pos, tr_pos, bl_pos, br_pos;
Eigen::Vector4f tl_pos;
Eigen::Vector4f tr_pos;
Eigen::Vector4f bl_pos;
Eigen::Vector4f br_pos;
bool has_bl = false;
bool has_br = false;
bool has_tl = false;
@ -1147,7 +1150,6 @@ public:
uint32_t indices[PSVR_NUM_LEDS];
public:
~Helper()
{
m_permutator_reset(&mp);
@ -1269,7 +1271,7 @@ typedef struct blob_data
static void
sample_line(cv::Mat &src, cv::Point2i start, cv::Point2i end, int *inside_length)
sample_line(cv::Mat &src, const cv::Point2i &start, const cv::Point2i &end, int *inside_length)
{
// use bresenhams algorithm to sample the
// pixels between two points in an image
@ -1589,7 +1591,7 @@ process(TrackerPSVR &t, struct xrt_frame *xf)
// Convert our 2d point + disparities into 3d points.
std::vector<blob_data_t> blob_datas;
if (t.l_blobs.size() > 0) {
if (!t.l_blobs.empty()) {
for (uint32_t i = 0; i < t.l_blobs.size(); i++) {
float disp = t.r_blobs[i].pt.x - t.l_blobs[i].pt.x;
cv::Vec4d xydw(t.l_blobs[i].pt.x, t.l_blobs[i].pt.y, disp, 1.0f);
@ -1785,7 +1787,7 @@ process(TrackerPSVR &t, struct xrt_frame *xf)
t.last_vertices.push_back(solved[i]);
}
if (t.last_vertices.size() > 0) {
if (!t.last_vertices.empty()) {
filter_update(&t.last_vertices, t.track_filters, dt / 1000.0f);
}
@ -1999,7 +2001,7 @@ t_psvr_node_break_apart(struct xrt_frame_node *node)
extern "C" void
t_psvr_node_destroy(struct xrt_frame_node *node)
{
auto t_ptr = container_of(node, TrackerPSVR, node);
auto *t_ptr = container_of(node, TrackerPSVR, node);
os_thread_helper_destroy(&t_ptr->oth);

View file

@ -99,7 +99,7 @@ struct t_stereo_camera_calibration
};
/*!
* Allocates a new stereo calibration data, unreferences the old @p calib.
* Allocates a new stereo calibration data, unreferences the old data pointed to by @p out_c.
*
* Also initializes t_camera_calibration::distortion_num in t_stereo_camera_calibration::view, only 5 and 14 is
* accepted.
@ -107,7 +107,7 @@ struct t_stereo_camera_calibration
* @public @memberof t_stereo_camera_calibration
*/
void
t_stereo_camera_calibration_alloc(struct t_stereo_camera_calibration **calib, uint32_t distortion_num);
t_stereo_camera_calibration_alloc(struct t_stereo_camera_calibration **out_c, uint32_t distortion_num);
/*!
* Only to be called by @p t_stereo_camera_calibration_reference.
@ -188,7 +188,7 @@ t_stereo_camera_calibration_save_v1(FILE *calib_file, struct t_stereo_camera_cal
* @relates t_stereo_camera_calibration
*/
bool
t_stereo_camera_calibration_from_json_v2(cJSON *json, struct t_stereo_camera_calibration **out_data);
t_stereo_camera_calibration_from_json_v2(cJSON *json, struct t_stereo_camera_calibration **out_stereo);
/*!
* Convert the given stereo calibration data into a json object in v2 format.
@ -196,7 +196,7 @@ t_stereo_camera_calibration_from_json_v2(cJSON *json, struct t_stereo_camera_cal
* @relates t_stereo_camera_calibration
*/
bool
t_stereo_camera_calibration_to_json_v2(cJSON **out_json, struct t_stereo_camera_calibration *data);
t_stereo_camera_calibration_to_json_v2(cJSON **out_cjson, struct t_stereo_camera_calibration *data);
/*!

View file

@ -7,10 +7,6 @@
* @ingroup st_prober
*/
#ifdef _MSC_VER
#define _CRT_SECURE_NO_WARNINGS
#endif
#include <xrt/xrt_device.h>
#include "xrt/xrt_settings.h"
#include "xrt/xrt_config.h"
@ -311,10 +307,10 @@ u_config_json_get_tracking_overrides(struct u_config_json *json,
bad |= !get_obj_str(override, "tracker_device_serial", o->tracker_device_serial, XRT_DEVICE_NAME_LEN);
char override_type[256];
bad |= !get_obj_str(override, "type", override_type, 256);
if (strncmp(override_type, "direct", 256) == 0) {
bad |= !get_obj_str(override, "type", override_type, sizeof(override_type));
if (strncmp(override_type, "direct", sizeof(override_type) - 1) == 0) {
o->override_type = XRT_TRACKING_OVERRIDE_DIRECT;
} else if (strncmp(override_type, "attached", 256) == 0) {
} else if (strncmp(override_type, "attached", sizeof(override_type) - 1) == 0) {
o->override_type = XRT_TRACKING_OVERRIDE_ATTACHED;
}

View file

@ -83,10 +83,10 @@ u_distortion_cardboard_calculate(const struct u_cardboard_distortion_arguments *
// Tan-angle to texture coordinates
// clang-format off
l_values.texture.size.x = tan(-args->fov.angle_left) + tan(args->fov.angle_right);
l_values.texture.size.y = tan(args->fov.angle_up) + tan(-args->fov.angle_down);
l_values.texture.offset.x = tan(-args->fov.angle_left);
l_values.texture.offset.y = tan(-args->fov.angle_down);
l_values.texture.size.x = tanf(-args->fov.angle_left) + tanf(args->fov.angle_right);
l_values.texture.size.y = tanf(args->fov.angle_up) + tanf(-args->fov.angle_down);
l_values.texture.offset.x = tanf(-args->fov.angle_left);
l_values.texture.offset.y = tanf(-args->fov.angle_down);
// clang-format on
// Fix up views not covering the entire screen.
@ -118,10 +118,10 @@ u_distortion_cardboard_calculate(const struct u_cardboard_distortion_arguments *
// Tanangle to texture coordinates
// clang-format off
r_values.texture.size.x = tan(-args->fov.angle_left) + tan(args->fov.angle_right);
r_values.texture.size.y = tan(args->fov.angle_up) + tan(-args->fov.angle_down);
r_values.texture.offset.x = tan(-args->fov.angle_left);
r_values.texture.offset.y = tan(-args->fov.angle_down);
r_values.texture.size.x = tanf(-args->fov.angle_left) + tanf(args->fov.angle_right);
r_values.texture.size.y = tanf(args->fov.angle_up) + tanf(-args->fov.angle_down);
r_values.texture.offset.x = tanf(-args->fov.angle_left);
r_values.texture.offset.y = tanf(-args->fov.angle_down);
// clang-format on
// Fix up views not covering the entire screen.

View file

@ -301,10 +301,10 @@ u_compute_distortion_ns_p2d(struct u_ns_p2d_values *values, int view, float u, f
struct xrt_fov fov = values->fov[view];
float left_ray_bound = tan(fov.angle_left);
float right_ray_bound = tan(fov.angle_right);
float up_ray_bound = tan(fov.angle_up);
float down_ray_bound = tan(fov.angle_down);
float left_ray_bound = tanf(fov.angle_left);
float right_ray_bound = tanf(fov.angle_right);
float up_ray_bound = tanf(fov.angle_up);
float down_ray_bound = tanf(fov.angle_down);
float u_eye = math_map_ranges(x_ray, left_ray_bound, right_ray_bound, 0, 1);
@ -363,10 +363,10 @@ u_compute_distortion_ns_vipd(struct u_ns_vipd_values *values, int view, float u,
struct xrt_fov fov = values->fov[view];
float left_ray_bound = tan(fov.angle_left);
float right_ray_bound = tan(fov.angle_right);
float up_ray_bound = tan(fov.angle_up);
float down_ray_bound = tan(fov.angle_down);
float left_ray_bound = tanf(fov.angle_left);
float right_ray_bound = tanf(fov.angle_right);
float up_ray_bound = tanf(fov.angle_up);
float down_ray_bound = tanf(fov.angle_down);
// printf("%f %f", fov.angle_down, fov.angle_up);
float u_eye = math_map_ranges(x_ray, left_ray_bound, right_ray_bound, 0, 1);

View file

@ -66,7 +66,7 @@ u_file_get_config_dir(char *out_path, size_t out_path_size)
}
ssize_t
u_file_get_path_in_config_dir(const char *filename, char *out_path, size_t out_path_size)
u_file_get_path_in_config_dir(const char *suffix, char *out_path, size_t out_path_size)
{
char tmp[PATH_MAX];
ssize_t i = u_file_get_config_dir(tmp, sizeof(tmp));
@ -74,7 +74,7 @@ u_file_get_path_in_config_dir(const char *filename, char *out_path, size_t out_p
return -1;
}
return snprintf(out_path, out_path_size, "%s/%s", tmp, filename);
return snprintf(out_path, out_path_size, "%s/%s", tmp, suffix);
}
FILE *
@ -117,7 +117,7 @@ u_file_get_runtime_dir(char *out_path, size_t out_path_size)
}
ssize_t
u_file_get_path_in_runtime_dir(const char *filename, char *out_path, size_t out_path_size)
u_file_get_path_in_runtime_dir(const char *suffix, char *out_path, size_t out_path_size)
{
char tmp[PATH_MAX];
ssize_t i = u_file_get_runtime_dir(tmp, sizeof(tmp));
@ -125,7 +125,7 @@ u_file_get_path_in_runtime_dir(const char *filename, char *out_path, size_t out_
return -1;
}
return snprintf(out_path, out_path_size, "%s/%s", tmp, filename);
return snprintf(out_path, out_path_size, "%s/%s", tmp, suffix);
}
#endif

View file

@ -35,7 +35,7 @@ char *
u_file_read_content(FILE *file);
ssize_t
u_file_get_path_in_runtime_dir(const char *filename, char *out_path, size_t out_path_size);
u_file_get_path_in_runtime_dir(const char *suffix, char *out_path, size_t out_path_size);
#ifdef __cplusplus
}

View file

@ -34,7 +34,7 @@ struct u_hashmap_int
extern "C" int
u_hashmap_int_create(struct u_hashmap_int **out_hashmap_int)
{
auto hs = new u_hashmap_int;
auto *hs = new u_hashmap_int;
*out_hashmap_int = hs;
return 0;
}
@ -91,7 +91,7 @@ u_hashmap_int_clear_and_call_for_each(struct u_hashmap_int *hmi, u_hashmap_int_c
hmi->map.clear();
for (auto n : tmp) {
for (auto *n : tmp) {
cb(n, priv);
}
}

View file

@ -37,7 +37,7 @@ struct u_hashset
extern "C" int
u_hashset_create(struct u_hashset **out_hashset)
{
auto hs = new u_hashset;
auto *hs = new u_hashset;
*out_hashset = hs;
return 0;
}
@ -159,7 +159,7 @@ u_hashset_clear_and_call_for_each(struct u_hashset *hs, u_hashset_callback cb, v
hs->map.clear();
for (auto n : tmp) {
for (auto *n : tmp) {
cb(n, priv);
}
}

View file

@ -45,9 +45,7 @@ struct IdRingbufferIterator : public RandomAccessIteratorBase<const RingBufferHe
container_type *container_{nullptr};
IdRingbufferIterator(container_type *container, base &&iter_base)
: base(std::move(iter_base)), container_(container)
{}
IdRingbufferIterator(container_type *container, base &&iter_base) : base(iter_base), container_(container) {}
static Self
begin(container_type &container)

View file

@ -24,9 +24,8 @@ u_index_fifo_is_empty(struct u_index_fifo *uif)
{
if (uif->start == uif->end) {
return 1;
} else {
return 0;
}
return 0;
}
static inline int
@ -34,9 +33,8 @@ u_index_fifo_is_full(struct u_index_fifo *uif)
{
if (((uif->end + 1) % U_MAX_FIFO_INDICES) == uif->start) {
return 1;
} else {
return 0;
}
return 0;
}
static inline int

View file

@ -299,7 +299,7 @@ public:
}
bool
hasKey(const string &key)
hasKey(const string &key) const
{
return asObject().count(key) == 1;
}

View file

@ -442,7 +442,7 @@ pa_destroy(struct u_pacing_app *upa)
*/
xrt_result_t
u_pa_create(struct u_pacing_app **out_urt)
u_pa_create(struct u_pacing_app **out_upa)
{
struct pacing_app *pa = U_TYPED_CALLOC(struct pacing_app);
pa->base.predict = pa_predict;
@ -461,7 +461,7 @@ u_pa_create(struct u_pacing_app **out_urt)
pa->frames[i].frame_id = -1;
}
*out_urt = &pa->base;
*out_upa = &pa->base;
return XRT_SUCCESS;
}

View file

@ -675,7 +675,7 @@ const struct u_pc_display_timing_config U_PC_DISPLAY_TIMING_CONFIG_DEFAULT = {
xrt_result_t
u_pc_display_timing_create(uint64_t estimated_frame_period_ns,
const struct u_pc_display_timing_config *config,
struct u_pacing_compositor **out_uft)
struct u_pacing_compositor **out_upc)
{
struct pacing_compositor *pc = U_TYPED_CALLOC(struct pacing_compositor);
pc->base.predict = pc_predict;
@ -699,7 +699,7 @@ u_pc_display_timing_create(uint64_t estimated_frame_period_ns,
// Extra margin that is added to compositor time.
pc->margin_ns = config->margin_ns;
*out_uft = &pc->base;
*out_upc = &pc->base;
double estimated_frame_period_ms = ns_to_ms(estimated_frame_period_ns);
UPC_LOG_I("Created compositor pacing (%.2fms)", estimated_frame_period_ms);

View file

@ -177,7 +177,7 @@ pc_destroy(struct u_pacing_compositor *upc)
*/
xrt_result_t
u_pc_fake_create(uint64_t estimated_frame_period_ns, uint64_t now_ns, struct u_pacing_compositor **out_uft)
u_pc_fake_create(uint64_t estimated_frame_period_ns, uint64_t now_ns, struct u_pacing_compositor **out_upc)
{
struct fake_timing *ft = U_TYPED_CALLOC(struct fake_timing);
ft->base.predict = pc_predict;
@ -200,7 +200,7 @@ u_pc_fake_create(uint64_t estimated_frame_period_ns, uint64_t now_ns, struct u_p
ft->last_display_time_ns = now_ns + U_TIME_1MS_IN_NS * 50.0;
// Return value.
*out_uft = &ft->base;
*out_upc = &ft->base;
U_LOG_I("Created fake timing");

View file

@ -40,7 +40,8 @@ split_frame(struct xrt_frame_sink *xfs, struct xrt_frame *xf)
int one_frame_width = xf->width / 2;
struct xrt_rect left, right;
struct xrt_rect left;
struct xrt_rect right;
left.offset.h = 0;
left.offset.w = 0;

View file

@ -125,10 +125,7 @@ public:
}
std::string needle{str};
auto it = std::find_if(vec.begin(), vec.end(), [needle](const char *elt) { return needle == elt; });
if (it != vec.end()) {
return true;
}
return false;
return it != vec.end();
}
/*!

View file

@ -42,11 +42,11 @@ namespace detail {
// copy and move as you wish
HistoryBufConstIterator(HistoryBufConstIterator const &) = default;
HistoryBufConstIterator(HistoryBufConstIterator &&) = default;
HistoryBufConstIterator(HistoryBufConstIterator &&) noexcept = default;
HistoryBufConstIterator &
operator=(HistoryBufConstIterator const &) = default;
HistoryBufConstIterator &
operator=(HistoryBufConstIterator &&) = default;
operator=(HistoryBufConstIterator &&) noexcept = default;
//! Implicit conversion from a non-const iterator
HistoryBufConstIterator(const HistoryBufIterator<T, MaxSize> &other);
@ -119,19 +119,19 @@ namespace detail {
static Self
begin(container_type &container, const RingBufferHelper &helper)
{
return {&container, std::move(base::begin(helper))};
return {&container, base::begin(helper)};
}
//! Construct the "past the end" iterator that can be decremented safely
static Self
end(container_type &container, const RingBufferHelper &helper)
{
return {&container, std::move(base::end(helper))};
return {&container, base::end(helper)};
}
// for use internally
HistoryBufConstIterator(container_type *container, base &&iter_base)
: base(std::move(iter_base)), container_(container)
: base(iter_base), container_(container)
{}
container_type *container_{nullptr};
};

View file

@ -41,11 +41,11 @@ namespace detail {
// copy and move as you wish
HistoryBufIterator(HistoryBufIterator const &) = default;
HistoryBufIterator(HistoryBufIterator &&) = default;
HistoryBufIterator(HistoryBufIterator &&) noexcept = default;
HistoryBufIterator &
operator=(HistoryBufIterator const &) = default;
HistoryBufIterator &
operator=(HistoryBufIterator &&) = default;
operator=(HistoryBufIterator &&) noexcept = default;
//! Is this iterator valid?
bool
@ -115,19 +115,18 @@ namespace detail {
static Self
begin(container_type &container, const RingBufferHelper &helper)
{
return {&container, std::move(base::begin(helper))};
return {&container, base::begin(helper)};
}
//! Construct the "past the end" iterator that can be decremented safely
static Self
end(container_type &container, const RingBufferHelper &helper)
{
return {&container, std::move(base::end(helper))};
return {&container, base::end(helper)};
}
// for use internally
HistoryBufIterator(container_type *container, base &&iter_base)
: base(std::move(iter_base)), container_(container)
HistoryBufIterator(container_type *container, base &&iter_base) : base(iter_base), container_(container)
{}
container_type *container_{nullptr};
};
@ -136,7 +135,7 @@ namespace detail {
inline typename HistoryBufIterator<T, MaxSize>::reference
HistoryBufIterator<T, MaxSize>::operator*() const
{
auto ptr = container_->get_at_index(base::index());
auto *ptr = container_->get_at_index(base::index());
if (ptr == nullptr) {
throw std::out_of_range("Iterator index out of range");
}

View file

@ -109,9 +109,9 @@ struct group
*/
static inline struct group *
group(struct u_worker_group *uwp)
group(struct u_worker_group *uwg)
{
return (struct group *)uwp;
return (struct group *)uwg;
}
static inline struct pool *
@ -464,11 +464,11 @@ u_worker_group_create(struct u_worker_thread_pool *uwtp)
}
void
u_worker_group_push(struct u_worker_group *uwp, u_worker_group_func_t f, void *data)
u_worker_group_push(struct u_worker_group *uwg, u_worker_group_func_t f, void *data)
{
XRT_TRACE_MARKER();
struct group *g = group(uwp);
struct group *g = group(uwg);
struct pool *p = pool(g->uwtp);
os_mutex_lock(&p->mutex);
@ -476,7 +476,7 @@ u_worker_group_push(struct u_worker_group *uwp, u_worker_group_func_t f, void *d
os_mutex_unlock(&p->mutex);
//! @todo Don't wait all, wait one.
u_worker_group_wait_all(uwp);
u_worker_group_wait_all(uwg);
os_mutex_lock(&p->mutex);
}
@ -492,11 +492,11 @@ u_worker_group_push(struct u_worker_group *uwp, u_worker_group_func_t f, void *d
}
void
u_worker_group_wait_all(struct u_worker_group *uwp)
u_worker_group_wait_all(struct u_worker_group *uwg)
{
XRT_TRACE_MARKER();
struct group *g = group(uwp);
struct group *g = group(uwg);
struct pool *p = pool(g->uwtp);
os_mutex_lock(&p->mutex);
@ -517,18 +517,18 @@ u_worker_group_wait_all(struct u_worker_group *uwp)
}
void
u_worker_group_destroy(struct u_worker_group *uwp)
u_worker_group_destroy(struct u_worker_group *uwg)
{
XRT_TRACE_MARKER();
struct group *g = group(uwp);
struct group *g = group(uwg);
assert(g->base.reference.count == 0);
u_worker_group_wait_all(uwp);
u_worker_group_wait_all(uwg);
u_worker_thread_pool_reference(&g->uwtp, NULL);
os_cond_destroy(&g->waiting.cond);
free(uwp);
free(uwg);
}

View file

@ -60,7 +60,8 @@ _get_color_coeffs(struct u_vive_values *values, const cJSON *coeffs, uint8_t eye
static void
_get_pose_from_pos_x_z(const cJSON *obj, struct xrt_pose *pose)
{
struct xrt_vec3 plus_x, plus_z;
struct xrt_vec3 plus_x;
struct xrt_vec3 plus_z;
JSON_VEC3(obj, "plus_x", &plus_x);
JSON_VEC3(obj, "plus_z", &plus_z);
JSON_VEC3(obj, "position", &pose->position);
@ -248,7 +249,8 @@ _get_cameras(struct vive_config *d, const cJSON *cameras_json)
if (!found_camera_json) {
U_LOG_W("HMD is Index, but no cameras in json file!");
return false;
} else if (!succeeded_parsing_json) {
}
if (!succeeded_parsing_json) {
U_LOG_E("Failed to parse Index camera calibration!");
return false;
}
@ -264,7 +266,8 @@ _get_cameras(struct vive_config *d, const cJSON *cameras_json)
d->cameras.view[1].headref = camera_to_head;
// Calculate where in the right camera space the left camera is.
struct xrt_pose invert, left_in_right;
struct xrt_pose invert;
struct xrt_pose left_in_right;
math_pose_invert(&d->cameras.view[1].headref, &invert);
math_pose_transform(&d->cameras.view[0].headref, &invert, &left_in_right);
d->cameras.left_in_right = left_in_right;
@ -321,7 +324,9 @@ vive_get_stereo_camera_calibration(struct vive_config *d,
}
struct xrt_vec3 pos = d->cameras.opencv.position;
struct xrt_vec3 x = {1, 0, 0}, y = {0, 1, 0}, z = {0, 0, 1};
struct xrt_vec3 x = XRT_VEC3_UNIT_X;
struct xrt_vec3 y = XRT_VEC3_UNIT_Y;
struct xrt_vec3 z = XRT_VEC3_UNIT_Z;
math_quat_rotate_vec3(&d->cameras.opencv.orientation, &x, &x);
math_quat_rotate_vec3(&d->cameras.opencv.orientation, &y, &y);
math_quat_rotate_vec3(&d->cameras.opencv.orientation, &z, &z);

View file

@ -209,7 +209,7 @@ vive_config_parse(struct vive_config *d, char *json_string, enum u_logging_level
* Free any allocated resources on this config.
*/
void
vive_config_teardown(struct vive_config *d);
vive_config_teardown(struct vive_config *config);
struct vive_controller_device;

View file

@ -540,7 +540,7 @@ VkResult
vk_create_device(struct vk_bundle *vk,
int forced_index,
bool only_compute,
VkQueueGlobalPriorityEXT global_priorty,
VkQueueGlobalPriorityEXT global_priority,
struct u_string_list *required_device_ext_list,
struct u_string_list *optional_device_ext_list,
const struct vk_device_features *optional_device_features);
@ -953,7 +953,7 @@ vk_create_compute_pipeline(struct vk_bundle *vk,
* Does error logging.
*/
VkResult
vk_create_command_buffer(struct vk_bundle *vk, VkCommandBuffer *out_cmd);
vk_create_command_buffer(struct vk_bundle *vk, VkCommandBuffer *out_command_buffer);
/*!
* Destroys a command buffer, takes the cmd_pool_mutex.

View file

@ -116,8 +116,6 @@ vk_xf_readback_pool_try_create_new_frame(struct vk_bundle *vk, struct vk_image_r
im->base_frame.height = extent.height;
im->base_frame.size = stride * extent.height;
im->base_frame.format = pool->desired_format;
return;
}
/*

View file

@ -29,18 +29,16 @@ vk_get_semaphore_handle_type(struct vk_bundle *vk)
#if defined(XRT_GRAPHICS_SYNC_HANDLE_IS_FD)
if (vk->external.binary_semaphore_opaque_fd) {
return VK_EXTERNAL_SEMAPHORE_HANDLE_TYPE_OPAQUE_FD_BIT;
} else {
return 0;
}
#elif defined(XRT_GRAPHICS_SYNC_HANDLE_IS_WIN32_HANDLE)
if (vk->external.binary_semaphore_win32_handle) {
return VK_EXTERNAL_SEMAPHORE_HANDLE_TYPE_OPAQUE_WIN32_BIT;
} else {
return 0;
}
#else
#error "Need to port semaphore type code."
#endif
return 0;
}
#ifdef VK_KHR_timeline_semaphore
@ -50,18 +48,15 @@ vk_get_timeline_semaphore_handle_type(struct vk_bundle *vk)
#if defined(XRT_GRAPHICS_SYNC_HANDLE_IS_FD)
if (vk->external.timeline_semaphore_opaque_fd) {
return VK_EXTERNAL_SEMAPHORE_HANDLE_TYPE_OPAQUE_FD_BIT;
} else {
return 0;
}
#elif defined(XRT_GRAPHICS_SYNC_HANDLE_IS_WIN32_HANDLE)
if (vk->external.timeline_semaphore_win32_handle) {
return VK_EXTERNAL_SEMAPHORE_HANDLE_TYPE_OPAQUE_WIN32_BIT;
} else {
return 0;
}
#else
#error "Need to port semaphore type code."
#endif
return 0;
}
#endif

View file

@ -233,7 +233,8 @@ client_gl_compositor_layer_stereo_projection(struct xrt_compositor *xc,
const struct xrt_layer_data *data)
{
struct client_gl_compositor *c = client_gl_compositor(xc);
struct xrt_swapchain *l_xscn, *r_xscn;
struct xrt_swapchain *l_xscn;
struct xrt_swapchain *r_xscn;
assert(data->type == XRT_LAYER_STEREO_PROJECTION);
@ -256,7 +257,10 @@ client_gl_compositor_layer_stereo_projection_depth(struct xrt_compositor *xc,
const struct xrt_layer_data *data)
{
struct client_gl_compositor *c = client_gl_compositor(xc);
struct xrt_swapchain *l_xscn, *r_xscn, *l_d_xscn, *r_d_xscn;
struct xrt_swapchain *l_xscn;
struct xrt_swapchain *r_xscn;
struct xrt_swapchain *l_d_xscn;
struct xrt_swapchain *r_d_xscn;
assert(data->type == XRT_LAYER_STEREO_PROJECTION_DEPTH);

View file

@ -49,7 +49,7 @@ struct xrt_swapchain *
client_gl_memobj_swapchain_create(struct xrt_compositor *xc,
const struct xrt_swapchain_create_info *info,
struct xrt_swapchain_native *xscn,
struct client_gl_swapchain **out_sc);
struct client_gl_swapchain **out_cglsc);
#ifdef __cplusplus

View file

@ -451,7 +451,8 @@ client_vk_compositor_layer_stereo_projection(struct xrt_compositor *xc,
const struct xrt_layer_data *data)
{
struct client_vk_compositor *c = client_vk_compositor(xc);
struct xrt_swapchain *l_xscn, *r_xscn;
struct xrt_swapchain *l_xscn;
struct xrt_swapchain *r_xscn;
assert(data->type == XRT_LAYER_STEREO_PROJECTION);
@ -472,7 +473,10 @@ client_vk_compositor_layer_stereo_projection_depth(struct xrt_compositor *xc,
const struct xrt_layer_data *data)
{
struct client_vk_compositor *c = client_vk_compositor(xc);
struct xrt_swapchain *l_xscn, *r_xscn, *l_d_xscn, *r_d_xscn;
struct xrt_swapchain *l_xscn;
struct xrt_swapchain *r_xscn;
struct xrt_swapchain *l_d_xscn;
struct xrt_swapchain *r_d_xscn;
assert(data->type == XRT_LAYER_STEREO_PROJECTION_DEPTH);

View file

@ -732,10 +732,8 @@ renderer_resize(struct comp_renderer *r)
renderer_close_renderings_and_fences(r);
return;
}
renderer_ensure_images_and_renderings(r, true); // Force recreate.
return;
// Force recreate.
renderer_ensure_images_and_renderings(r, true);
}
static void
@ -1572,8 +1570,9 @@ comp_renderer_destroy(struct comp_renderer **ptr_r)
}
void
comp_renderer_add_debug_vars(struct comp_renderer *r)
comp_renderer_add_debug_vars(struct comp_renderer *self)
{
struct comp_renderer *r = self;
r->mirror_to_debug_gui.push_every_frame_out_of_X = 2;
u_frame_times_widget_init(&r->mirror_to_debug_gui.push_frame_times, 0.f, 0.f);

View file

@ -149,7 +149,8 @@ update_fusion(struct arduino_device *ad,
timepoint_ns timestamp_ns,
time_duration_ns delta_ns)
{
struct xrt_vec3 accel, gyro;
struct xrt_vec3 accel;
struct xrt_vec3 gyro;
m_imu_pre_filter_data(&ad->pre_filter, &sample->accel, &sample->gyro, &accel, &gyro);
ad->device_time += (uint64_t)sample->delta * 1000;
@ -231,7 +232,8 @@ arduino_run_thread(void *ptr)
{
struct arduino_device *ad = (struct arduino_device *)ptr;
uint8_t buffer[20];
timepoint_ns then_ns, now_ns;
timepoint_ns then_ns;
timepoint_ns now_ns;
struct arduino_parsed_input input; // = {0};
// wait for a package to sync up, it's discarded but that's okay.

View file

@ -88,7 +88,8 @@ update_fusion(struct daydream_device *dd,
time_duration_ns delta_ns)
{
struct xrt_vec3 accel, gyro;
struct xrt_vec3 accel;
struct xrt_vec3 gyro;
m_imu_pre_filter_data(&dd->pre_filter, &sample->accel, &sample->gyro, &accel, &gyro);
DAYDREAM_DEBUG(dd,

View file

@ -103,9 +103,7 @@ euroc_device(struct xrt_device *xdev)
static void
euroc_device_update_inputs(struct xrt_device *xdev)
{
return;
}
{}
//! Corrections specific for original euroc datasets and Kimera.
//! If your datasets comes from a different camera you should probably

View file

@ -453,7 +453,8 @@ euroc_player_push_next_frame(struct euroc_player *ep)
{
bool stereo = ep->playback.stereo;
struct xrt_frame *left_xf = NULL, *right_xf = NULL;
struct xrt_frame *left_xf = NULL;
struct xrt_frame *right_xf = NULL;
euroc_player_load_next_frame(ep, true, left_xf);
if (stereo) {
// TODO: Some SLAM systems expect synced frames, but that's not an
@ -787,8 +788,6 @@ euroc_player_destroy(struct xrt_frame_node *node)
m_ff_vec3_f32_free(&ep->accel_ff);
free(ep);
return;
}

View file

@ -209,7 +209,7 @@ OpticalSystem::SolveDisplayUVToRenderUV(const Vector2 &inputUV, Vector2 const &i
Vector2
OpticalSystem::DisplayUVToRenderUVPreviousSeed(Vector2 inputUV)
OpticalSystem::DisplayUVToRenderUVPreviousSeed(const Vector2 &inputUV)
{
// if we don't find a point we generate it and add it to our list
Vector2 curDisplayUV;

View file

@ -20,7 +20,7 @@ public:
LoadOpticalData(struct ns_3d_eye *eye);
Vector3
GetEyePosition()
GetEyePosition() const
{
return eyePosition;
}
@ -35,20 +35,20 @@ public:
SolveDisplayUVToRenderUV(const Vector2 &inputUV, Vector2 const &initialGuess, int iterations);
Vector2
DisplayUVToRenderUVPreviousSeed(Vector2 inputUV);
DisplayUVToRenderUVPreviousSeed(const Vector2 &inputUV);
void
RegenerateMesh();
void
UpdateEyePosition(const Vector3 pos)
UpdateEyePosition(const Vector3 &pos)
{
eyePosition.x = pos.x;
eyePosition.y = pos.y;
eyePosition.z = pos.z;
}
const Vector4
Vector4
GetCameraProjection()
{
return cameraProjection;
@ -62,7 +62,7 @@ public:
}
void
UpdateClipToWorld(Matrix4x4 eyeRotationMatrix)
UpdateClipToWorld(const Matrix4x4 &eyeRotationMatrix)
{
Matrix4x4 eyeToWorld = Matrix4x4::Translate(eyePosition) * eyeRotationMatrix;
eyeToWorld.m02 *= -1;
@ -73,8 +73,11 @@ public:
Vector3 eyePosition;
inline void
ViewportPointToRayDirection(Vector2 UV, Vector3 cameraPosition, Matrix4x4 clipToWorld, Vector3 &out)
static inline void
ViewportPointToRayDirection(const Vector2 &UV,
const Vector3 &cameraPosition,
const Matrix4x4 &clipToWorld,
Vector3 &out)
{
Vector3 tmp;
tmp.x = UV.x - 0.5f;
@ -84,7 +87,6 @@ public:
float mag = dir.Magnitude();
out = dir / mag;
return;
}
private:
@ -107,14 +109,18 @@ private:
// supporting functions
inline Vector3
Project(Vector3 v1, Vector3 v2)
Project(const Vector3 &v1, const Vector3 &v2)
{
Vector3 v2Norm = (v2 / v2.Magnitude());
return v2Norm * Vector3::Dot(v1, v2Norm);
}
inline float
intersectLineSphere(Vector3 Origin, Vector3 Direction, Vector3 spherePos, float SphereRadiusSqrd, bool frontSide = true)
intersectLineSphere(const Vector3 &Origin,
const Vector3 &Direction,
const Vector3 &spherePos,
float SphereRadiusSqrd,
bool frontSide = true)
{
Vector3 L = spherePos - Origin;
Vector3 offsetFromSphereCenterToRay = Project(L, Direction) - L;
@ -125,7 +131,7 @@ intersectLineSphere(Vector3 Origin, Vector3 Direction, Vector3 spherePos, float
}
inline float
intersectPlane(Vector3 n, Vector3 p0, Vector3 l0, Vector3 l)
intersectPlane(const Vector3 &n, const Vector3 &p0, const Vector3 &l0, const Vector3 &l)
{
float denom = Vector3::Dot((Vector3::Zero() - n), l);

View file

@ -84,7 +84,7 @@ public:
};
inline Vector3
operator-(Vector3 &rhs) const
operator-(const Vector3 &rhs) const
{
Vector3 ret;
ret.x = (x - rhs.x);
@ -158,7 +158,7 @@ public:
}
inline static float
Angle(Vector3 v0, Vector3 v1)
Angle(const Vector3 &v0, const Vector3 &v1)
{
Vector3 dir0 = v0.Normalized();
Vector3 dir1 = v1.Normalized();
@ -196,7 +196,7 @@ public:
}
inline static Vector3
Reflect(Vector3 inDirection, Vector3 inNormal)
Reflect(const Vector3 &inDirection, const Vector3 &inNormal)
{
return inNormal * -2.F * Dot(inNormal, inDirection) + inDirection;
}
@ -235,7 +235,7 @@ public:
inline void
rotate(Vector3 axis, float radians)
rotate(const Vector3 &axis, float radians)
{
float cos_theta = cosf(radians);
float sin_theta = sinf(radians);
@ -251,7 +251,7 @@ public:
}
inline Vector3
Cross(const Vector3 in) const
Cross(const Vector3 &in) const
{
Vector3 ret;
ret.x = y * in.z - z * in.y;
@ -489,7 +489,7 @@ public:
}
inline Matrix4x4 // Until clang-format-11 is on the CI.
operator*(const Matrix4x4 &_in)
operator*(const Matrix4x4 &_in) const
{
Matrix4x4 ret;
ret.m00 = (m00 * _in.m00) + (m01 * _in.m10) + (m02 * _in.m20) + (m03 * _in.m30);
@ -536,7 +536,7 @@ public:
}
inline static Matrix4x4
Translate(Vector3 vector)
Translate(const Vector3 &vector)
{
Matrix4x4 m;
m.m00 = 1.f;
@ -559,7 +559,7 @@ public:
}
inline Vector3
MultiplyVector(Vector3 vector) const
MultiplyVector(const Vector3 &vector) const
{
Vector3 res;
res.x = m00 * vector.x + m01 * vector.y + m02 * vector.z;
@ -569,7 +569,7 @@ public:
}
inline Vector3
MultiplyPoint3x4(Vector3 point) const
MultiplyPoint3x4(const Vector3 &point) const
{
Vector3 res;
res.x = m00 * point.x + m01 * point.y + m02 * point.z + m03;
@ -744,7 +744,7 @@ public:
class Ray
{
public:
inline Ray(Vector3 origin, Vector3 direction)
inline Ray(const Vector3 &origin, Vector3 direction)
{
m_Origin = origin;
direction.Normalize();
@ -754,7 +754,7 @@ public:
}
inline Vector3
GetPoint(float distance)
GetPoint(float distance) const
{
return m_Origin + m_Direction * distance;
}
@ -872,7 +872,10 @@ public:
Vector3 euler;
const static float PI_OVER_2 = M_PI * 0.5f;
const static float EPSILON = 1e-10f;
float sqw, sqx, sqy, sqz;
float sqw;
float sqx;
float sqy;
float sqz;
// quick conversion to Euler angles to give tilt to user
sqw = in.w * in.w;
@ -974,7 +977,7 @@ public:
}
inline static Quaternion
AxisAngle(Vector3 axis, float angle)
AxisAngle(const Vector3 &axis, float angle)
{
float halfAngle = angle * .5f;
float s = (float)sin(halfAngle);
@ -987,7 +990,7 @@ public:
}
inline static Quaternion
LookAt(Vector3 sourcePoint, Vector3 destPoint)
LookAt(const Vector3 &sourcePoint, const Vector3 &destPoint)
{
Vector3 forwardVector = (destPoint - sourcePoint).Normalized();
@ -1007,7 +1010,7 @@ public:
}
inline static Quaternion
QuaternionLookRotation(Vector3 forward, Vector3 Up)
QuaternionLookRotation(const Vector3 &forward, const Vector3 &Up)
{
Vector3 vector1 = forward.Normalized();
@ -1066,10 +1069,13 @@ public:
}
inline static Quaternion
FromMatrix(const Matrix4x4 m)
FromMatrix(const Matrix4x4 &m)
{
float tr = m.m00 + m.m11 + m.m22;
float qx, qy, qz, qw;
float qx;
float qy;
float qz;
float qw;
if (tr > 0) {
float S = sqrtf(tr + 1.f) * 2.f;
@ -1166,7 +1172,7 @@ public:
//}
inline static Quaternion
FromToRotation(Vector3 dir0, Vector3 dir1)
FromToRotation(const Vector3 &dir0, const Vector3 &dir1)
{
Vector3 axis = dir0.Cross(dir1).Normalized();
float angle = Vector3::Angle(dir0, dir1);

View file

@ -107,7 +107,6 @@ good:
assert(fabsf(out_fov.angle_right) < M_PI_2);
memcpy(left_fov, &out_fov, sizeof(struct xrt_fov));
memcpy(right_fov, &out_fov, sizeof(struct xrt_fov));
return;
}
bool
@ -641,7 +640,8 @@ ns_hmd_create(const char *config_path)
// avoid unintended consequences. As soon as you have a specific reason to support it, go ahead and support it.
ns->base.hmd->blend_mode_count = idx;
uint64_t start, end;
uint64_t start;
uint64_t end;
start = os_monotonic_get_ns();
u_distortion_mesh_fill_in_compute(&ns->base);

View file

@ -1295,7 +1295,8 @@ psmv_get_calibration_zcm1(struct psmv_device *psmv)
struct psmv_calibration_zcm1 data;
uint8_t *dst = (uint8_t *)&data;
int ret = 0;
size_t src_offset, dst_offset;
size_t src_offset;
size_t dst_offset;
for (int i = 0; i < 3; i++) {
struct psmv_calibration_part part = {0};
@ -1511,7 +1512,8 @@ psmv_get_calibration_zcm2(struct psmv_device *psmv)
struct psmv_calibration_zcm2 data;
uint8_t *dst = (uint8_t *)&data;
int ret = 0;
size_t src_offset, dst_offset;
size_t src_offset;
size_t dst_offset;
for (int i = 0; i < 2; i++) {
struct psmv_calibration_part part = {0};

View file

@ -177,7 +177,8 @@ qwerty_get_tracked_pose(struct xrt_device *xd,
qd->yaw_delta = 0;
qd->pitch_delta = 0;
struct xrt_quat x_rotation, y_rotation;
struct xrt_quat x_rotation;
struct xrt_quat y_rotation;
const struct xrt_vec3 x_axis = XRT_VEC3_UNIT_X;
const struct xrt_vec3 y_axis = XRT_VEC3_UNIT_Y;
math_quat_from_angle_vector(x_look_speed, &x_axis, &x_rotation);
@ -231,7 +232,8 @@ struct qwerty_hmd *
qwerty_hmd_create(void)
{
enum u_device_alloc_flags flags = U_DEVICE_ALLOC_HMD | U_DEVICE_ALLOC_TRACKING_NONE;
size_t input_count = 1, output_count = 0;
size_t input_count = 1;
size_t output_count = 0;
struct qwerty_hmd *qh = U_DEVICE_ALLOCATE(struct qwerty_hmd, flags, input_count, output_count);
assert(qh);

View file

@ -46,7 +46,9 @@ find_qwerty_system(struct xrt_device **xdevs, size_t xdev_count)
static struct qwerty_device *
default_qwerty_device(struct xrt_device **xdevs, size_t xdev_count, struct qwerty_system *qsys)
{
int head, left, right;
int head;
int left;
int right;
head = left = right = XRT_DEVICE_ROLE_UNASSIGNED;
u_device_assign_xdev_roles(xdevs, xdev_count, &head, &left, &right);
@ -72,7 +74,9 @@ default_qwerty_device(struct xrt_device **xdevs, size_t xdev_count, struct qwert
static struct qwerty_controller *
default_qwerty_controller(struct xrt_device **xdevs, size_t xdev_count, struct qwerty_system *qsys)
{
int head, left, right;
int head;
int left;
int right;
head = left = right = XRT_DEVICE_ROLE_UNASSIGNED;
u_device_assign_xdev_roles(xdevs, xdev_count, &head, &left, &right);

View file

@ -29,7 +29,7 @@
#define __USE_MISC // SOL_TCP on C11
#endif
#ifndef _BSD_SOURCE
#define _BSD_SOURCE // same, but for musl
#define _BSD_SOURCE // same, but for musl // NOLINT
#endif
#include <netinet/tcp.h>
@ -85,7 +85,8 @@ int
do_accept(struct r_hub *r)
{
struct sockaddr_in addr = {0};
int ret, conn_fd;
int ret;
int conn_fd;
socklen_t addr_length = (socklen_t)sizeof(addr);
ret = accept(r->accept_fd, (struct sockaddr *)&addr, &addr_length);
@ -286,7 +287,8 @@ r_remote_connection_read_one(struct r_remote_connection *rc, struct r_remote_dat
ssize_t ret = read(rc->fd, ptr, size - current);
if (ret < 0) {
return ret;
} else if (ret > 0) {
}
if (ret > 0) {
current += (size_t)ret;
} else {
U_LOG_I("Disconnected!");
@ -309,7 +311,8 @@ r_remote_connection_write_one(struct r_remote_connection *rc, const struct r_rem
ssize_t ret = write(rc->fd, ptr, size - current);
if (ret < 0) {
return ret;
} else if (ret > 0) {
}
if (ret > 0) {
current += (size_t)ret;
} else {
U_LOG_I("Disconnected!");

View file

@ -269,7 +269,8 @@ update_imu(struct vive_device *d, const void *buffer)
const struct vive_imu_sample *sample = report->sample;
uint8_t last_seq = d->imu.sequence;
d->imu.ts_received_ns = os_monotonic_get_ns();
int i, j;
int i;
int j;
/*
* The three samples are updated round-robin. New messages

View file

@ -72,7 +72,8 @@ read_packets(struct wmr_bt_controller *d)
if (size < 0) {
WMR_ERROR(d, "WMR Controller (Bluetooth): Error reading from device");
return false;
} else if (size == 0) {
}
if (size == 0) {
WMR_TRACE(d, "WMR Controller (Bluetooth): No data to read from device");
return true; // No more messages, return.
}
@ -163,8 +164,11 @@ wmr_read_fw_block(struct wmr_bt_controller *d, uint8_t blk_id, uint8_t **out_dat
{
struct wmr_controller_fw_cmd_response fw_cmd_response;
uint8_t *data, *data_pos, *data_end;
uint32_t data_size, remain;
uint8_t *data;
uint8_t *data_pos;
uint8_t *data_end;
uint32_t data_size;
uint32_t remain;
struct wmr_controller_fw_cmd fw_cmd;
memset(&fw_cmd, 0, sizeof(fw_cmd));
@ -224,7 +228,8 @@ wmr_read_fw_block(struct wmr_bt_controller *d, uint8_t blk_id, uint8_t **out_dat
static bool
read_controller_config(struct wmr_bt_controller *d)
{
unsigned char *data = NULL, *config_json_block;
unsigned char *data = NULL;
unsigned char *config_json_block;
size_t data_size;
int ret;
@ -234,7 +239,7 @@ read_controller_config(struct wmr_bt_controller *d)
// USB PID/VID are visible in them, but it's not clear
// what the layout is and we don't use them currently,
// so this if 0 code is just exemplary.
// Read serials
ret = wmr_read_fw_block(d, 0x03, &data, &data_size);
if (ret < 0 || data == NULL)

View file

@ -140,9 +140,13 @@ struct wmr_camera
static bool
compute_frame_size(struct wmr_camera *cam)
{
int i, cams_found = 0;
int width, height;
size_t F, n_packets, leftover;
int i;
int cams_found = 0;
int width;
int height;
size_t F;
size_t n_packets;
size_t leftover;
F = 26;
@ -402,7 +406,8 @@ wmr_camera_open(struct xrt_prober_device *dev_holo,
DRV_TRACE_MARKER();
struct wmr_camera *cam = calloc(1, sizeof(struct wmr_camera));
int res, i;
int res;
int i;
cam->log_level = log_level;
cam->debug_gain = DEFAULT_GAIN;
@ -572,7 +577,8 @@ wmr_camera_stop(struct wmr_camera *cam)
{
DRV_TRACE_MARKER();
int res, i;
int res;
int i;
if (!cam->running) {
return true;

View file

@ -20,7 +20,7 @@
*/
static inline void
vec3_from_wmr_controller_accel(int32_t sample[3], struct xrt_vec3 *out_vec)
vec3_from_wmr_controller_accel(const int32_t sample[3], struct xrt_vec3 *out_vec)
{
// Reverb G1 observation: 1g is approximately 490,000.
@ -31,7 +31,7 @@ vec3_from_wmr_controller_accel(int32_t sample[3], struct xrt_vec3 *out_vec)
static inline void
vec3_from_wmr_controller_gyro(int32_t sample[3], struct xrt_vec3 *out_vec)
vec3_from_wmr_controller_gyro(const int32_t sample[3], struct xrt_vec3 *out_vec)
{
out_vec->x = (float)sample[0] * 0.00001f;
out_vec->y = (float)sample[1] * 0.00001f;

View file

@ -124,8 +124,6 @@ hololens_sensors_decode_packet(struct wmr_hmd *wh,
for (int i = 0; i < 4; i++) {
pkt->video_timestamp[i] = read64(&buffer);
}
return;
}
@ -349,7 +347,8 @@ hololens_sensors_read_packets(struct wmr_hmd *wh)
if (size < 0) {
WMR_ERROR(wh, "Error reading from Hololens Sensors device. Call to os_hid_read returned %i", size);
return false;
} else if (size == 0) {
}
if (size == 0) {
WMR_TRACE(wh, "No more data to read");
return true; // No more messages, return.
} else {
@ -432,7 +431,8 @@ control_read_packets(struct wmr_hmd *wh)
WMR_ERROR(wh, "Error reading from companion (HMD control) device. Call to os_hid_read returned %i",
size);
return false;
} else if (size == 0) {
}
if (size == 0) {
WMR_TRACE(wh, "No more data to read");
return true; // No more messages, return.
} else {
@ -797,7 +797,8 @@ wmr_read_config_raw(struct wmr_hmd *wh, uint8_t **out_data, size_t *out_size)
unsigned char meta[84];
uint8_t *data;
int size, data_size;
int size;
int data_size;
size = wmr_read_config_part(wh, 0x06, meta, sizeof(meta));
WMR_DEBUG(wh, "(0x06, meta) => %d", size);
@ -837,7 +838,8 @@ wmr_read_config(struct wmr_hmd *wh)
{
DRV_TRACE_MARKER();
unsigned char *data = NULL, *config_json_block;
unsigned char *data = NULL;
unsigned char *config_json_block;
size_t data_size;
int ret;
@ -1117,7 +1119,10 @@ compute_distortion_bounds(struct wmr_hmd *wh,
assert(view == 0 || view == 1);
float tanangle_left = 0.0f, tanangle_right = 0.0f, tanangle_up = 0.0f, tanangle_down = 0.0f;
float tanangle_left = 0.0f;
float tanangle_right = 0.0f;
float tanangle_up = 0.0f;
float tanangle_down = 0.0f;
const struct wmr_distortion_eye_config *ec = wh->config.eye_params + view;
struct wmr_hmd_distortion_params *distortion_params = wh->distortion_params + view;
@ -1241,7 +1246,8 @@ wmr_hmd_create(enum wmr_headset_type hmd_type,
enum u_device_alloc_flags flags =
(enum u_device_alloc_flags)(U_DEVICE_ALLOC_HMD | U_DEVICE_ALLOC_TRACKING_NONE);
int ret = 0, i;
int ret = 0;
int i;
int eye;
struct wmr_hmd *wh = U_DEVICE_ALLOCATE(struct wmr_hmd, flags, 1, 0);

View file

@ -357,7 +357,10 @@ wmr_source_create(struct xrt_frame_context *xfctx, struct xrt_prober_device *dev
}
void
wmr_source_push_imu_packet(struct xrt_fs *xfs, uint64_t ts[4], struct xrt_vec3 accels[4], struct xrt_vec3 gyros[4])
wmr_source_push_imu_packet(struct xrt_fs *xfs,
const uint64_t ts[4],
struct xrt_vec3 accels[4],
struct xrt_vec3 gyros[4])
{
DRV_TRACE_MARKER();

View file

@ -32,7 +32,10 @@ wmr_source_create(struct xrt_frame_context *xfctx, struct xrt_prober_device *dev
//! @todo IMU data should be generated from within the data source, but right
//! now we need this function because it is being generated from wmr_hmd
void
wmr_source_push_imu_packet(struct xrt_fs *xfs, uint64_t ts[4], struct xrt_vec3 accels[4], struct xrt_vec3 gyros[4]);
wmr_source_push_imu_packet(struct xrt_fs *xfs,
const uint64_t ts[4],
struct xrt_vec3 accels[4],
struct xrt_vec3 gyros[4]);
/*!
* @}

View file

@ -19,7 +19,7 @@ extern "C" {
typedef void *EGLDisplay;
typedef void *EGLConfig;
typedef void *EGLContext;
typedef void (*__eglMustCastToProperFunctionPointerType)(void);
typedef void (*__eglMustCastToProperFunctionPointerType)(void); // NOLINT
typedef __eglMustCastToProperFunctionPointerType (*PFNEGLGETPROCADDRESSPROC)(const char *proc);
struct time_state;
@ -34,7 +34,7 @@ xrt_gfx_provider_create_gl_egl(struct xrt_compositor_native *xcn,
EGLDisplay display,
EGLConfig config,
EGLContext context,
PFNEGLGETPROCADDRESSPROC getProcAddress,
PFNEGLGETPROCADDRESSPROC get_gl_procaddr,
struct xrt_compositor_gl **out_xcgl);
#ifdef __cplusplus

View file

@ -17,7 +17,7 @@ extern "C" {
#endif
typedef struct _XDisplay Display;
typedef struct _XDisplay Display; // NOLINT
typedef void *GLXFBConfig;
typedef void *GLXDrawable;
typedef void *GLXContext;

View file

@ -34,7 +34,7 @@ typedef void *EGLDisplay;
typedef void *EGLContext;
typedef void *EGLConfig;
typedef unsigned int EGLenum;
typedef void (*__eglMustCastToProperFunctionPointerType)(void);
typedef void (*__eglMustCastToProperFunctionPointerType)(void); // NOLINT
typedef __eglMustCastToProperFunctionPointerType (*PFNEGLGETPROCADDRESSPROC)(const char *procname);
#endif

View file

@ -347,7 +347,7 @@ ipc_server_main_android(struct ipc_server **ps, void (*startup_complete_callback
* @ingroup ipc_server
*/
void
ipc_server_set_active_client(struct ipc_server *s, int active_client_index);
ipc_server_set_active_client(struct ipc_server *s, int client_id);
/*!
* Called by client threads to set a session to active.
@ -379,7 +379,7 @@ ipc_server_update_state(struct ipc_server *s);
* @ingroup ipc_server
*/
void *
ipc_server_client_thread(void *_cs);
ipc_server_client_thread(void *_ics);
/*!
* This destroys the native compositor for this client and any extra objects

View file

@ -76,7 +76,8 @@ create_listen_socket(struct ipc_server_mainloop *ml, int *out_fd)
{
// no fd provided
struct sockaddr_un addr;
int fd, ret;
int fd;
int ret;
fd = socket(PF_UNIX, SOCK_STREAM, 0);
if (fd < 0) {
@ -143,7 +144,8 @@ create_listen_socket(struct ipc_server_mainloop *ml, int *out_fd)
static int
init_listen_socket(struct ipc_server_mainloop *ml)
{
int fd = -1, ret;
int fd = -1;
int ret;
ml->listen_socket = -1;
ret = get_systemd_socket(ml, &fd);

View file

@ -326,9 +326,8 @@ ipc_receive_handles_graphics_sync(struct ipc_message_channel *imc,
//! @todo Temporary hack to send no handles.
if (handle_count == 0) {
return ipc_receive(imc, out_data, size);
} else {
return ipc_receive_fds(imc, out_data, size, out_handles, handle_count);
}
return ipc_receive_fds(imc, out_data, size, out_handles, handle_count);
}
xrt_result_t
@ -341,9 +340,8 @@ ipc_send_handles_graphics_sync(struct ipc_message_channel *imc,
//! @todo Temporary hack to send no handles.
if (handle_count == 0) {
return ipc_send(imc, data, size);
} else {
return ipc_send_fds(imc, data, size, handles, handle_count);
}
return ipc_send_fds(imc, data, size, handles, handle_count);
}
#else

View file

@ -132,7 +132,7 @@ gui_ogl_sink_create(const char *name, struct xrt_frame_context *xfctx, struct xr
* @ingroup gui
*/
void
gui_ogl_sink_update(struct gui_ogl_texture *);
gui_ogl_sink_update(struct gui_ogl_texture * /*tex*/);
/*!
* Push the scene to the top of the lists.

View file

@ -124,7 +124,9 @@ gui_ogl_sink_update(struct gui_ogl_texture *tex)
return;
}
GLint w, h, stride;
GLint w;
GLint h;
GLint stride;
uint8_t *data;
w = frame->width;

View file

@ -214,7 +214,8 @@ scene_render(struct gui_scene *scene, struct gui_program *p)
struct xrt_tracking_override *o = &ts->overrides[ts->gui_edit_override_index];
igBegin("Tracker Device Offset", NULL, 0);
int target = -1, tracker = -1;
int target = -1;
int tracker = -1;
if (get_indices(p, ts, o, &target, &tracker)) {
igText("Editing %s [%s] <- %s [%s]", p->xdevs[target]->str, o->target_device_serial,
p->xdevs[tracker]->str, o->tracker_device_serial);

View file

@ -33,7 +33,8 @@ oxr_xrCreateSession(XrInstance instance, const XrSessionCreateInfo *createInfo,
XrResult ret;
struct oxr_instance *inst;
struct oxr_session *sess, **link;
struct oxr_session *sess;
struct oxr_session **link;
struct oxr_logger log;
OXR_VERIFY_INSTANCE_AND_INIT_LOG(&log, instance, inst, "xrCreateSession");
@ -64,7 +65,8 @@ oxr_xrDestroySession(XrSession session)
{
OXR_TRACE_MARKER();
struct oxr_session *sess, **link;
struct oxr_session *sess;
struct oxr_session **link;
struct oxr_instance *inst;
struct oxr_logger log;
OXR_VERIFY_SESSION_AND_INIT_LOG(&log, session, sess, "xrDestroySession");

View file

@ -14,7 +14,7 @@ extern "C" {
#endif
#define _OXR_VERIFY_AND_SET_AND_INIT(log, thing, new_thing, oxr_thing, THING, name, lookup) \
#define OXR_VERIFY_AND_SET_AND_INIT(log, thing, new_thing, oxr_thing, THING, name, lookup) \
do { \
oxr_log_init(log, name); \
if (thing == XR_NULL_HANDLE) { \
@ -31,7 +31,7 @@ extern "C" {
oxr_log_set_instance(log, lookup); \
} while (0)
#define _OXR_VERIFY_SET(log, arg, new_arg, oxr_thing, THING) \
#define OXR_VERIFY_SET(log, arg, new_arg, oxr_thing, THING) \
do { \
if (arg == XR_NULL_HANDLE) { \
return oxr_error(log, XR_ERROR_HANDLE_INVALID, "(" #arg " == NULL)"); \
@ -50,30 +50,30 @@ extern "C" {
// clang-format off
#define OXR_VERIFY_INSTANCE_AND_INIT_LOG(log, thing, new_thing, name) \
_OXR_VERIFY_AND_SET_AND_INIT(log, thing, new_thing, oxr_instance, INSTANCE, name, new_thing)
OXR_VERIFY_AND_SET_AND_INIT(log, thing, new_thing, oxr_instance, INSTANCE, name, new_thing)
#define OXR_VERIFY_MESSENGER_AND_INIT_LOG(log, thing, new_thing, name) \
_OXR_VERIFY_AND_SET_AND_INIT(log, thing, new_thing, oxr_messenger, MESSENGER, name, new_thing->inst)
OXR_VERIFY_AND_SET_AND_INIT(log, thing, new_thing, oxr_messenger, MESSENGER, name, new_thing->inst)
#define OXR_VERIFY_SESSION_AND_INIT_LOG(log, thing, new_thing, name) \
_OXR_VERIFY_AND_SET_AND_INIT(log, thing, new_thing, oxr_session, SESSION, name, new_thing->sys->inst)
OXR_VERIFY_AND_SET_AND_INIT(log, thing, new_thing, oxr_session, SESSION, name, new_thing->sys->inst)
#define OXR_VERIFY_SPACE_AND_INIT_LOG(log, thing, new_thing, name) \
_OXR_VERIFY_AND_SET_AND_INIT(log, thing, new_thing, oxr_space, SPACE, name, new_thing->sess->sys->inst)
OXR_VERIFY_AND_SET_AND_INIT(log, thing, new_thing, oxr_space, SPACE, name, new_thing->sess->sys->inst)
#define OXR_VERIFY_ACTION_AND_INIT_LOG(log, thing, new_thing, name) \
_OXR_VERIFY_AND_SET_AND_INIT(log, thing, new_thing, oxr_action, ACTION, name, new_thing->act_set->inst)
OXR_VERIFY_AND_SET_AND_INIT(log, thing, new_thing, oxr_action, ACTION, name, new_thing->act_set->inst)
#define OXR_VERIFY_SWAPCHAIN_AND_INIT_LOG(log, thing, new_thing, name) \
_OXR_VERIFY_AND_SET_AND_INIT(log, thing, new_thing, oxr_swapchain, SWAPCHAIN, name, new_thing->sess->sys->inst)
OXR_VERIFY_AND_SET_AND_INIT(log, thing, new_thing, oxr_swapchain, SWAPCHAIN, name, new_thing->sess->sys->inst)
#define OXR_VERIFY_ACTIONSET_AND_INIT_LOG(log, thing, new_thing, name) \
_OXR_VERIFY_AND_SET_AND_INIT(log, thing, new_thing, oxr_action_set, ACTIONSET, name, new_thing->inst)
OXR_VERIFY_AND_SET_AND_INIT(log, thing, new_thing, oxr_action_set, ACTIONSET, name, new_thing->inst)
#define OXR_VERIFY_HAND_TRACKER_AND_INIT_LOG(log, thing, new_thing, name) \
_OXR_VERIFY_AND_SET_AND_INIT(log, thing, new_thing, oxr_hand_tracker, HTRACKER, name, new_thing->sess->sys->inst)
OXR_VERIFY_AND_SET_AND_INIT(log, thing, new_thing, oxr_hand_tracker, HTRACKER, name, new_thing->sess->sys->inst)
// clang-format on
#define OXR_VERIFY_INSTANCE_NOT_NULL(log, arg, new_arg) _OXR_VERIFY_SET(log, arg, new_arg, oxr_instance, INSTANCE);
#define OXR_VERIFY_MESSENGER_NOT_NULL(log, arg, new_arg) _OXR_VERIFY_SET(log, arg, new_arg, oxr_messenger, MESSENGER);
#define OXR_VERIFY_SESSION_NOT_NULL(log, arg, new_arg) _OXR_VERIFY_SET(log, arg, new_arg, oxr_session, SESSION);
#define OXR_VERIFY_SPACE_NOT_NULL(log, arg, new_arg) _OXR_VERIFY_SET(log, arg, new_arg, oxr_space, SPACE);
#define OXR_VERIFY_ACTION_NOT_NULL(log, arg, new_arg) _OXR_VERIFY_SET(log, arg, new_arg, oxr_action, ACTION);
#define OXR_VERIFY_SWAPCHAIN_NOT_NULL(log, arg, new_arg) _OXR_VERIFY_SET(log, arg, new_arg, oxr_swapchain, SWAPCHAIN);
#define OXR_VERIFY_ACTIONSET_NOT_NULL(log, arg, new_arg) _OXR_VERIFY_SET(log, arg, new_arg, oxr_action_set, ACTIONSET);
#define OXR_VERIFY_INSTANCE_NOT_NULL(log, arg, new_arg) OXR_VERIFY_SET(log, arg, new_arg, oxr_instance, INSTANCE);
#define OXR_VERIFY_MESSENGER_NOT_NULL(log, arg, new_arg) OXR_VERIFY_SET(log, arg, new_arg, oxr_messenger, MESSENGER);
#define OXR_VERIFY_SESSION_NOT_NULL(log, arg, new_arg) OXR_VERIFY_SET(log, arg, new_arg, oxr_session, SESSION);
#define OXR_VERIFY_SPACE_NOT_NULL(log, arg, new_arg) OXR_VERIFY_SET(log, arg, new_arg, oxr_space, SPACE);
#define OXR_VERIFY_ACTION_NOT_NULL(log, arg, new_arg) OXR_VERIFY_SET(log, arg, new_arg, oxr_action, ACTION);
#define OXR_VERIFY_SWAPCHAIN_NOT_NULL(log, arg, new_arg) OXR_VERIFY_SET(log, arg, new_arg, oxr_swapchain, SWAPCHAIN);
#define OXR_VERIFY_ACTIONSET_NOT_NULL(log, arg, new_arg) OXR_VERIFY_SET(log, arg, new_arg, oxr_action_set, ACTIONSET);
/*!
* Checks if a required extension is enabled.
@ -203,13 +203,16 @@ oxr_verify_full_path(struct oxr_logger *log, const char *path, size_t length, co
* Verify a single path level that sits inside of a fixed sized array.
*/
XrResult
oxr_verify_fixed_size_single_level_path(struct oxr_logger *, const char *path, uint32_t array_size, const char *name);
oxr_verify_fixed_size_single_level_path(struct oxr_logger * /*log*/,
const char *path,
uint32_t array_size,
const char *name);
/*!
* Verify an arbitrary UTF-8 string that sits inside of a fixed sized array.
*/
XrResult
oxr_verify_localized_name(struct oxr_logger *, const char *string, uint32_t array_size, const char *name);
oxr_verify_localized_name(struct oxr_logger * /*log*/, const char *string, uint32_t array_size, const char *name);
/*!
* Verify a set of subaction paths for action creation.
@ -248,16 +251,18 @@ oxr_verify_view_config_type(struct oxr_logger *log,
const char *view_conf_name);
XrResult
oxr_verify_XrSessionCreateInfo(struct oxr_logger *, const struct oxr_instance *, const XrSessionCreateInfo *);
oxr_verify_XrSessionCreateInfo(struct oxr_logger * /*log*/,
const struct oxr_instance * /*inst*/,
const XrSessionCreateInfo * /*createInfo*/);
#if defined(XR_USE_PLATFORM_XLIB) && defined(XR_USE_GRAPHICS_API_OPENGL)
XrResult
oxr_verify_XrGraphicsBindingOpenGLXlibKHR(struct oxr_logger *, const XrGraphicsBindingOpenGLXlibKHR *);
oxr_verify_XrGraphicsBindingOpenGLXlibKHR(struct oxr_logger * /*log*/, const XrGraphicsBindingOpenGLXlibKHR * /*next*/);
#endif // defined(XR_USE_PLATFORM_XLIB) && defined(XR_USE_GRAPHICS_API_OPENGL)
#if defined(XR_USE_GRAPHICS_API_VULKAN)
XrResult
oxr_verify_XrGraphicsBindingVulkanKHR(struct oxr_logger *, const XrGraphicsBindingVulkanKHR *);
oxr_verify_XrGraphicsBindingVulkanKHR(struct oxr_logger * /*log*/, const XrGraphicsBindingVulkanKHR * /*next*/);
#endif // defined(XR_USE_GRAPHICS_API_VULKAN)
#if defined(XR_USE_PLATFORM_EGL) && defined(XR_USE_GRAPHICS_API_OPENGL)

View file

@ -557,15 +557,14 @@ do_io_bindings(struct oxr_binding *binding_point,
matched_path, //
outputs, //
output_count); //
} else {
return do_inputs( //
binding_point, //
xdev, //
xbp, //
matched_path, //
inputs, //
input_count); //
}
return do_inputs( //
binding_point, //
xdev, //
xbp, //
matched_path, //
inputs, //
input_count); //
}
static struct xrt_binding_profile *

View file

@ -191,7 +191,7 @@ oxr_input_transform_process(const struct oxr_input_transform *transforms,
* @public @memberof oxr_input_transform
*/
bool
oxr_input_transform_init_root(struct oxr_input_transform *transform, const enum xrt_input_type input_type);
oxr_input_transform_init_root(struct oxr_input_transform *transform, enum xrt_input_type input_type);
/*!
* Allocate a transform to get the X component of a Vec2.

View file

@ -182,7 +182,9 @@ oxr_instance_create(struct oxr_logger *log,
{
struct oxr_instance *inst = NULL;
struct xrt_device *xdevs[NUM_XDEVS] = {0};
int xinst_ret, m_ret, h_ret;
int xinst_ret;
int m_ret;
int h_ret;
xrt_result_t xret;
XrResult ret;

View file

@ -815,9 +815,9 @@ oxr_swapchain_to_openxr(struct oxr_swapchain *sc)
}
XrResult
oxr_create_swapchain(struct oxr_logger *,
oxr_create_swapchain(struct oxr_logger * /*log*/,
struct oxr_session *sess,
const XrSwapchainCreateInfo *,
const XrSwapchainCreateInfo * /*createInfo*/,
struct oxr_swapchain **out_swapchain);
@ -1007,9 +1007,9 @@ oxr_session_populate_gl_xlib(struct oxr_logger *log,
#if defined(XR_USE_GRAPHICS_API_OPENGL) || defined(XR_USE_GRAPHICS_API_OPENGL_ES)
XrResult
oxr_swapchain_gl_create(struct oxr_logger *,
oxr_swapchain_gl_create(struct oxr_logger * /*log*/,
struct oxr_session *sess,
const XrSwapchainCreateInfo *,
const XrSwapchainCreateInfo * /*createInfo*/,
struct oxr_swapchain **out_swapchain);
#endif // XR_USE_GRAPHICS_API_OPENGL || XR_USE_GRAPHICS_API_OPENGL_ES
@ -1081,9 +1081,9 @@ oxr_session_populate_vk(struct oxr_logger *log,
struct oxr_session *sess);
XrResult
oxr_swapchain_vk_create(struct oxr_logger *,
oxr_swapchain_vk_create(struct oxr_logger * /*log*/,
struct oxr_session *sess,
const XrSwapchainCreateInfo *,
const XrSwapchainCreateInfo * /*createInfo*/,
struct oxr_swapchain **out_swapchain);
#endif

View file

@ -274,7 +274,8 @@ oxr_space_get_pure_relation(struct oxr_logger *log,
struct xrt_device *head_xdev = GET_XDEV_BY_ROLE(spc->sess->sys, head);
*out_xdev = head_xdev;
return oxr_space_ref_get_pure_relation(log, spc->sess, spc->space_type, head_xdev, time, out_relation);
} else if (spc->space_type == OXR_SPACE_TYPE_ACTION) {
}
if (spc->space_type == OXR_SPACE_TYPE_ACTION) {
struct oxr_action_input *input = NULL;
oxr_action_get_pose_input(spc->sess, spc->act_key, &spc->subaction_paths, &input);

View file

@ -212,7 +212,8 @@ oxr_create_swapchain(struct oxr_logger *log,
return oxr_error(log, XR_ERROR_FEATURE_UNSUPPORTED,
"Specified swapchain creation flag is valid, "
"but not supported");
} else if (xret == XRT_ERROR_SWAPCHAIN_FORMAT_UNSUPPORTED) {
}
if (xret == XRT_ERROR_SWAPCHAIN_FORMAT_UNSUPPORTED) {
return oxr_error(log, XR_ERROR_SWAPCHAIN_FORMAT_UNSUPPORTED,
"Specified swapchain format is not supported");
}

View file

@ -148,7 +148,8 @@ static void
p_udev_enumerate_usb(struct prober *p, struct udev *udev)
{
struct udev_enumerate *enumerate;
struct udev_list_entry *devices, *dev_list_entry;
struct udev_list_entry *devices;
struct udev_list_entry *dev_list_entry;
enumerate = udev_enumerate_new(udev);
udev_enumerate_add_match_subsystem(enumerate, "usb");
@ -253,7 +254,8 @@ static void
p_udev_enumerate_v4l2(struct prober *p, struct udev *udev)
{
struct udev_enumerate *enumerate;
struct udev_list_entry *devices, *dev_list_entry;
struct udev_list_entry *devices;
struct udev_list_entry *dev_list_entry;
enumerate = udev_enumerate_new(udev);
udev_enumerate_add_match_subsystem(enumerate, "video4linux");
@ -371,7 +373,8 @@ static void
p_udev_enumerate_hidraw(struct prober *p, struct udev *udev)
{
struct udev_enumerate *enumerate;
struct udev_list_entry *devices, *dev_list_entry;
struct udev_list_entry *devices;
struct udev_list_entry *dev_list_entry;
enumerate = udev_enumerate_new(udev);
udev_enumerate_add_match_subsystem(enumerate, "hidraw");
@ -383,7 +386,9 @@ p_udev_enumerate_hidraw(struct prober *p, struct udev *udev)
{
struct prober_device *pdev = NULL;
struct udev_device *raw_dev = NULL;
uint16_t vendor_id, product_id, interface;
uint16_t vendor_id;
uint16_t product_id;
uint16_t interface;
uint8_t dev_class = 0;
uint16_t usb_bus = 0;
uint16_t usb_addr = 0;
@ -497,7 +502,8 @@ p_udev_get_usb_hid_address(struct udev_device *raw_dev,
uint16_t *out_usb_bus,
uint16_t *out_usb_addr)
{
uint16_t dummy_vendor, dummy_product;
uint16_t dummy_vendor;
uint16_t dummy_product;
struct udev_device *usb_dev;
if (bus_type != HIDRAW_BUS_USB) {
@ -549,7 +555,8 @@ p_udev_get_and_parse_uevent(struct udev_device *raw_dev,
struct udev_device *hid_dev;
char *serial_utf8 = NULL;
uint64_t bluetooth_serial = 0;
uint16_t vendor_id = 0, product_id = 0;
uint16_t vendor_id = 0;
uint16_t product_id = 0;
char product_name[sizeof(*out_product_name)];
uint32_t bus_type;
const char *uevent;
@ -626,7 +633,9 @@ p_udev_try_usb_relation_get_address(struct udev_device *raw_dev,
uint16_t *out_usb_addr,
struct udev_device **out_usb_device)
{
struct udev_device *parent_dev, *usb_interface, *usb_device;
struct udev_device *parent_dev;
struct udev_device *usb_interface;
struct udev_device *usb_device;
parent_dev = udev_device_get_parent(raw_dev);
usb_interface = udev_device_get_parent_with_subsystem_devtype(raw_dev, "usb", "usb_interface");
@ -664,7 +673,8 @@ p_udev_try_usb_relation_get_address(struct udev_device *raw_dev,
static int
p_udev_get_vendor_id_product(struct udev_device *usb_dev, uint16_t *out_vendor_id, uint16_t *out_product_id)
{
uint16_t vendor_id, product_id;
uint16_t vendor_id;
uint16_t product_id;
int ret;
ret = p_udev_get_sysattr_u16_base16(usb_dev, "idVendor", &vendor_id);
@ -691,7 +701,9 @@ p_udev_get_usb_device_info(struct udev_device *usb_dev,
uint16_t *out_usb_bus,
uint16_t *out_usb_addr)
{
uint16_t vendor_id, product_id, dev_class;
uint16_t vendor_id;
uint16_t product_id;
uint16_t dev_class;
int ret;
// First get the vendor and product ids.
@ -727,7 +739,8 @@ p_udev_get_usb_device_info(struct udev_device *usb_dev,
static int
p_udev_get_usb_device_address_path(struct udev_device *usb_dev, uint16_t *out_usb_bus, uint16_t *out_usb_addr)
{
uint16_t bus = 0, addr = 0;
uint16_t bus = 0;
uint16_t addr = 0;
const char *dev_path = udev_device_get_devnode(usb_dev);
if (dev_path == NULL) {
@ -748,7 +761,8 @@ p_udev_get_usb_device_address_path(struct udev_device *usb_dev, uint16_t *out_us
static int
p_udev_get_usb_device_address_sysfs(struct udev_device *usb_dev, uint16_t *out_usb_bus, uint16_t *out_usb_addr)
{
uint16_t usb_bus = 0, usb_addr = 0;
uint16_t usb_bus = 0;
uint16_t usb_addr = 0;
int ret;
ret = p_udev_get_sysattr_u16_base16(usb_dev, "busnum", &usb_bus);

View file

@ -359,7 +359,7 @@ public:
}
}
struct profile_template *
static struct profile_template *
get_profile_template(enum xrt_device_name device_name)
{
for (int i = 0; i < NUM_PROFILE_TEMPLATES; i++) {
@ -1155,7 +1155,9 @@ CServerDriver_Monado::Init(vr::IVRDriverContext *pDriverContext)
ret = xrt_instance_select(m_xinst, xdevs, NUM_XDEVS);
int head, left, right;
int head;
int left;
int right;
u_device_assign_xdev_roles(xdevs, NUM_XDEVS, &head, &left, &right);
@ -1212,8 +1214,6 @@ CServerDriver_Monado::Cleanup()
if (m_xinst) {
xrt_instance_destroy(&m_xinst);
}
return;
}
void
@ -1247,7 +1247,7 @@ CServerDriver_Monado::HandleHapticEvent(vr::VREvent_t *event)
}
out.vibration.frequency = freq;
if (controller->m_output_controls.size() < 1) {
if (controller->m_output_controls.empty()) {
ovrd_log("Controller %s has no outputs\n", controller->m_xdev->str);
return;
}

View file

@ -42,7 +42,7 @@ t_instance_create_system_compositor(struct xrt_instance *xinst,
*/
int
xrt_instance_create(struct xrt_instance_info *i_info, struct xrt_instance **out_xinst)
xrt_instance_create(struct xrt_instance_info *ii, struct xrt_instance **out_xinst)
{
struct xrt_prober *xp = NULL;

View file

@ -28,7 +28,7 @@ t_instance_create_system_compositor_stub(struct xrt_instance *xinst,
*/
int
xrt_instance_create(struct xrt_instance_info *i_info, struct xrt_instance **out_xinst)
xrt_instance_create(struct xrt_instance_info *ii, struct xrt_instance **out_xinst)
{
struct xrt_prober *xp = NULL;

View file

@ -23,13 +23,13 @@ int
ipc_instance_create(struct xrt_instance_info *i_info, struct xrt_instance **out_xinst);
int
xrt_instance_create(struct xrt_instance_info *i_info, struct xrt_instance **out_xinst)
xrt_instance_create(struct xrt_instance_info *ii, struct xrt_instance **out_xinst)
{
u_trace_marker_init();
XRT_TRACE_MARKER();
return ipc_instance_create(i_info, out_xinst);
return ipc_instance_create(ii, out_xinst);
}
#else

View file

@ -213,7 +213,7 @@ TEST_CASE("u_template_historybuf")
SECTION("behavior when empty")
{
CHECK(buffer.empty());
CHECK(0 == buffer.size());
CHECK(0 == buffer.size()); // NOLINT
CHECK_FALSE(buffer.begin().valid());
CHECK_FALSE(buffer.end().valid());
CHECK(buffer.begin() == buffer.end());

View file

@ -15,7 +15,7 @@
TEST_CASE("u_template_historybuf")
{
auto buffer = u_id_ringbuffer_create(4);
auto *buffer = u_id_ringbuffer_create(4);
SECTION("behavior when empty")
{
CHECK(u_id_ringbuffer_is_empty(buffer));