Skip to content

Commit

Permalink
Replace a lot of memset with {} initializers
Browse files Browse the repository at this point in the history
  • Loading branch information
MaEtUgR authored and dagar committed Oct 15, 2019
1 parent b8f70e8 commit e843090
Show file tree
Hide file tree
Showing 12 changed files with 35 additions and 80 deletions.
6 changes: 2 additions & 4 deletions boards/emlid/navio2/navio_sysfs_rc_in/navio_sysfs_rc_in.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -70,9 +70,7 @@ class RcInput
_rcinput_pub(nullptr),
_channels(8), //D8R-II plus
_data{}
{
memset(_ch_fd, 0, sizeof(_ch_fd));
}
{ }
~RcInput()
{
work_cancel(HPWORK, &_work);
Expand Down Expand Up @@ -101,7 +99,7 @@ class RcInput
orb_advert_t _rcinput_pub;

int _channels;
int _ch_fd[input_rc_s::RC_INPUT_MAX_CHANNELS];
int _ch_fd[input_rc_s::RC_INPUT_MAX_CHANNELS] {};
struct input_rc_s _data;

int navio_rc_init();
Expand Down
3 changes: 1 addition & 2 deletions boards/parrot/bebop/flow/bebop_flow.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -77,8 +77,7 @@ void task_main(int argc, char *argv[])
{
_is_running = true;
int ret = 0;
struct frame_data frame;
memset(&frame, 0, sizeof(frame));
struct frame_data frame {};
uint32_t timeout_cnt = 0;

// Main loop
Expand Down
31 changes: 9 additions & 22 deletions boards/parrot/bebop/flow/video_device.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -146,8 +146,7 @@ int VideoDevice::close_device()

int VideoDevice::init_device()
{
struct v4l2_capability cap;
memset(&cap, 0, sizeof(cap));
struct v4l2_capability cap {};

int ret = ioctl(_fd, VIDIOC_QUERYCAP, &cap);

Expand Down Expand Up @@ -179,11 +178,8 @@ int VideoDevice::init_device()

int VideoDevice::init_crop()
{
struct v4l2_cropcap cropcap;
struct v4l2_crop crop;

memset(&cropcap, 0, sizeof(cropcap));
memset(&crop, 0, sizeof(crop));
struct v4l2_cropcap cropcap {};
struct v4l2_crop crop {};

cropcap.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
int ret = ioctl(_fd, VIDIOC_CROPCAP, &cropcap);
Expand All @@ -206,9 +202,7 @@ int VideoDevice::init_crop()
int VideoDevice::init_format()
{
usleep(10000);
struct v4l2_format fmt;

memset(&fmt, 0, sizeof(fmt));
struct v4l2_format fmt {};

fmt.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
fmt.fmt.pix.width = VIDEO_DEVICE_IMAGE_WIDTH;
Expand Down Expand Up @@ -253,9 +247,7 @@ int VideoDevice::init_format()

int VideoDevice::init_buffers()
{
struct v4l2_requestbuffers req;

memset(&req, 0, sizeof(req));
struct v4l2_requestbuffers req {};

req.count = _n_buffers;
req.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
Expand All @@ -276,8 +268,7 @@ int VideoDevice::init_buffers()
}

for (unsigned int i = 0; i < _n_buffers; ++i) {
struct v4l2_buffer buf;
memset(&buf, 0, sizeof(buf));
struct v4l2_buffer buf {};

buf.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
buf.memory = V4L2_MEMORY_MMAP;
Expand Down Expand Up @@ -306,9 +297,7 @@ int VideoDevice::init_buffers()
int VideoDevice::start_capturing()
{
for (unsigned int i = 0; i < _n_buffers; ++i) {
struct v4l2_buffer buf;

memset(&buf, 0, sizeof(buf));
struct v4l2_buffer buf {};

buf.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
buf.memory = V4L2_MEMORY_MMAP;
Expand Down Expand Up @@ -350,8 +339,7 @@ int VideoDevice::stop_capturing()

int VideoDevice::get_frame(struct frame_data &frame)
{
struct v4l2_buffer buf;
memset(&buf, 0, sizeof(buf));
struct v4l2_buffer buf {};

buf.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
buf.memory = V4L2_MEMORY_MMAP;
Expand Down Expand Up @@ -384,8 +372,7 @@ int VideoDevice::get_frame(struct frame_data &frame)

int VideoDevice::put_frame(struct frame_data &frame)
{
struct v4l2_buffer buf;
memset(&buf, 0, sizeof(buf));
struct v4l2_buffer buf {};

buf.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
buf.memory = V4L2_MEMORY_MMAP;
Expand Down
19 changes: 6 additions & 13 deletions platforms/common/work_queue/wqueue_test/wqueue_test.h
Original file line number Diff line number Diff line change
Expand Up @@ -46,15 +46,8 @@
class WQueueTest
{
public:
WQueueTest() :
_lpwork_done(false),
_hpwork_done(false)
{
memset(&_lpwork, 0, sizeof(_lpwork));
memset(&_hpwork, 0, sizeof(_hpwork));
};

~WQueueTest() {}
WQueueTest() = default;
~WQueueTest() = default;

int main();

Expand All @@ -66,8 +59,8 @@ class WQueueTest
void do_lp_work(void);
void do_hp_work(void);

bool _lpwork_done;
bool _hpwork_done;
work_s _lpwork;
work_s _hpwork;
bool _lpwork_done {false};
bool _hpwork_done {false};
work_s _lpwork {};
work_s _hpwork {};
};
3 changes: 1 addition & 2 deletions src/modules/commander/accelerometer_calibration.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -643,8 +643,7 @@ calibrate_return read_accelerometer_avg(int sensor_correction_sub, int (&subs)[m
}

unsigned counts[max_accel_sens] = { 0 };
float accel_sum[max_accel_sens][3];
memset(accel_sum, 0, sizeof(accel_sum));
float accel_sum[max_accel_sens][3] {};

unsigned errcount = 0;
struct sensor_correction_s sensor_correction; /**< sensor thermal corrections */
Expand Down
15 changes: 6 additions & 9 deletions src/modules/commander/commander_helper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -120,23 +120,20 @@ bool is_ground_rover(const struct vehicle_status_s *current_status)
return current_status->system_type == VEHICLE_TYPE_GROUND_ROVER;
}

static hrt_abstime blink_msg_end = 0; // end time for currently blinking LED message, 0 if no blink message
static hrt_abstime tune_end = 0; // end time of currently played tune, 0 for repeating tunes or silence
static int tune_current = TONE_STOP_TUNE; // currently playing tune, can be interrupted after tune_end
static unsigned int tune_durations[TONE_NUMBER_OF_TUNES];
static hrt_abstime blink_msg_end = 0; // end time for currently blinking LED message, 0 if no blink message
static hrt_abstime tune_end = 0; // end time of currently played tune, 0 for repeating tunes or silence
static int tune_current = TONE_STOP_TUNE; // currently playing tune, can be interrupted after tune_end
static unsigned int tune_durations[TONE_NUMBER_OF_TUNES] {};

static DevHandle h_leds;
static DevHandle h_buzzer;
static led_control_s led_control = {};
static led_control_s led_control {};
static orb_advert_t led_control_pub = nullptr;
static tune_control_s tune_control = {};
static tune_control_s tune_control {};
static orb_advert_t tune_control_pub = nullptr;

int buzzer_init()
{
tune_end = 0;
tune_current = 0;
memset(tune_durations, 0, sizeof(tune_durations));
tune_durations[TONE_NOTIFY_POSITIVE_TUNE] = 800000;
tune_durations[TONE_NOTIFY_NEGATIVE_TUNE] = 900000;
tune_durations[TONE_NOTIFY_NEUTRAL_TUNE] = 500000;
Expand Down
5 changes: 1 addition & 4 deletions src/modules/commander/gyro_calibration.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -82,12 +82,9 @@ static calibrate_return gyro_calibration_worker(int cancel_sub, void *data)
sensor_gyro_s gyro_report;
unsigned poll_errcount = 0;

struct sensor_correction_s sensor_correction; /**< sensor thermal corrections */
struct sensor_correction_s sensor_correction {}; /**< sensor thermal corrections */

if (orb_copy(ORB_ID(sensor_correction), worker_data->sensor_correction_sub, &sensor_correction) != 0) {
/* use default values */
memset(&sensor_correction, 0, sizeof(sensor_correction));

for (unsigned i = 0; i < 3; i++) {
sensor_correction.gyro_scale_0[i] = 1.0f;
sensor_correction.gyro_scale_1[i] = 1.0f;
Expand Down
3 changes: 1 addition & 2 deletions src/modules/muorb/krait/px4muorb_KraitRpcWrapper.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -96,8 +96,7 @@ int calc_timer_diff_to_dsp_us(int32_t *time_diff_us)
return -1;
}

char buffer[21];
memset(buffer, 0, sizeof(buffer));
char buffer[21] {};
int bytes_read = read(fd, buffer, sizeof(buffer));

if (bytes_read < 0) {
Expand Down
4 changes: 1 addition & 3 deletions src/modules/vmount/vmount.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -156,11 +156,9 @@ extern "C" __EXPORT int vmount_main(int argc, char *argv[]);
static int vmount_thread_main(int argc, char *argv[])
{
ParameterHandles param_handles;
Parameters params;
Parameters params {};
OutputConfig output_config;
ThreadData thread_data;
memset(&params, 0, sizeof(params));


InputTest *test_input = nullptr;

Expand Down
7 changes: 2 additions & 5 deletions src/modules/vtol_att_control/vtol_type.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -246,8 +246,7 @@ bool VtolType::set_idle_mc()
{

unsigned pwm_value = _params->idle_pwm_mc;
struct pwm_output_values pwm_values;
memset(&pwm_values, 0, sizeof(pwm_values));
struct pwm_output_values pwm_values {};

for (int i = 0; i < num_outputs_max; i++) {
if (is_channel_set(i, _params->vtol_motor_id)) {
Expand All @@ -265,9 +264,7 @@ bool VtolType::set_idle_mc()

bool VtolType::set_idle_fw()
{
struct pwm_output_values pwm_values;

memset(&pwm_values, 0, sizeof(pwm_values));
struct pwm_output_values pwm_values {};

for (int i = 0; i < num_outputs_max; i++) {
if (is_channel_set(i, _params->vtol_motor_id)) {
Expand Down
3 changes: 1 addition & 2 deletions src/systemcmds/motor_ramp/motor_ramp.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -274,8 +274,7 @@ int set_min_pwm(int fd, unsigned long max_channels, int pwm_value)
{
int ret;

struct pwm_output_values pwm_values;
memset(&pwm_values, 0, sizeof(pwm_values));
struct pwm_output_values pwm_values {};

pwm_values.channel_count = max_channels;

Expand Down
16 changes: 4 additions & 12 deletions src/systemcmds/pwm/pwm.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -415,9 +415,7 @@ pwm_main(int argc, char *argv[])
return 1;
}

struct pwm_output_values pwm_values;

memset(&pwm_values, 0, sizeof(pwm_values));
struct pwm_output_values pwm_values {};

pwm_values.channel_count = servo_count;

Expand Down Expand Up @@ -471,9 +469,7 @@ pwm_main(int argc, char *argv[])
return 1;
}

struct pwm_output_values pwm_values;

memset(&pwm_values, 0, sizeof(pwm_values));
struct pwm_output_values pwm_values {};

pwm_values.channel_count = servo_count;

Expand Down Expand Up @@ -526,9 +522,7 @@ pwm_main(int argc, char *argv[])
PX4_WARN("reading disarmed value of zero, disabling disarmed PWM");
}

struct pwm_output_values pwm_values;

memset(&pwm_values, 0, sizeof(pwm_values));
struct pwm_output_values pwm_values {};

pwm_values.channel_count = servo_count;

Expand Down Expand Up @@ -582,9 +576,7 @@ pwm_main(int argc, char *argv[])
return 1;
}

struct pwm_output_values pwm_values;

memset(&pwm_values, 0, sizeof(pwm_values));
struct pwm_output_values pwm_values {};

pwm_values.channel_count = servo_count;

Expand Down

0 comments on commit e843090

Please sign in to comment.