clang-tidy: partially fix cppcoreguidelines-pro-type-reinterpret-cast

This commit is contained in:
Daniel Agar
2019-10-27 19:15:56 -04:00
parent f5945d1185
commit 4192414576
16 changed files with 26 additions and 26 deletions

View File

@@ -164,7 +164,7 @@ void RcInput::stop()
void RcInput::cycle_trampoline(void *arg) void RcInput::cycle_trampoline(void *arg)
{ {
RcInput *dev = reinterpret_cast<RcInput *>(arg); RcInput *dev = static_cast<RcInput *>(arg);
dev->_cycle(); dev->_cycle();
} }

View File

@@ -291,7 +291,7 @@ ssize_t AEROFC_ADC::read(file *filp, char *buffer, size_t len)
void AEROFC_ADC::cycle_trampoline(void *arg) void AEROFC_ADC::cycle_trampoline(void *arg)
{ {
AEROFC_ADC *dev = reinterpret_cast<AEROFC_ADC * >(arg); AEROFC_ADC *dev = static_cast<AEROFC_ADC * >(arg);
dev->cycle(); dev->cycle();
} }

View File

@@ -44,7 +44,7 @@ ScheduledWorkItem::~ScheduledWorkItem()
void void
ScheduledWorkItem::schedule_trampoline(void *arg) ScheduledWorkItem::schedule_trampoline(void *arg)
{ {
ScheduledWorkItem *dev = reinterpret_cast<ScheduledWorkItem *>(arg); ScheduledWorkItem *dev = static_cast<ScheduledWorkItem *>(arg);
dev->ScheduleNow(); dev->ScheduleNow();
} }

View File

@@ -352,7 +352,7 @@ void
ArchPX4IOSerial::_dma_callback(DMA_HANDLE handle, uint8_t status, void *arg) ArchPX4IOSerial::_dma_callback(DMA_HANDLE handle, uint8_t status, void *arg)
{ {
if (arg != nullptr) { if (arg != nullptr) {
ArchPX4IOSerial *ps = reinterpret_cast<ArchPX4IOSerial *>(arg); ArchPX4IOSerial *ps = static_cast<ArchPX4IOSerial *>(arg);
ps->_do_rx_dma_callback(status); ps->_do_rx_dma_callback(status);
} }
@@ -387,7 +387,7 @@ int
ArchPX4IOSerial::_interrupt(int irq, void *context, void *arg) ArchPX4IOSerial::_interrupt(int irq, void *context, void *arg)
{ {
if (arg != nullptr) { if (arg != nullptr) {
ArchPX4IOSerial *instance = reinterpret_cast<ArchPX4IOSerial *>(arg); ArchPX4IOSerial *instance = static_cast<ArchPX4IOSerial *>(arg);
instance->_do_interrupt(); instance->_do_interrupt();
} }

View File

@@ -88,7 +88,7 @@ CameraCapture::capture_callback(uint32_t chan_index, hrt_abstime edge_time, uint
int int
CameraCapture::gpio_interrupt_routine(int irq, void *context, void *arg) CameraCapture::gpio_interrupt_routine(int irq, void *context, void *arg)
{ {
CameraCapture *dev = reinterpret_cast<CameraCapture *>(arg); CameraCapture *dev = static_cast<CameraCapture *>(arg);
dev->_trigger.chan_index = 0; dev->_trigger.chan_index = 0;
dev->_trigger.edge_time = hrt_absolute_time(); dev->_trigger.edge_time = hrt_absolute_time();
@@ -103,7 +103,7 @@ CameraCapture::gpio_interrupt_routine(int irq, void *context, void *arg)
void void
CameraCapture::publish_trigger_trampoline(void *arg) CameraCapture::publish_trigger_trampoline(void *arg)
{ {
CameraCapture *dev = reinterpret_cast<CameraCapture *>(arg); CameraCapture *dev = static_cast<CameraCapture *>(arg);
dev->publish_trigger(); dev->publish_trigger();
} }

View File

@@ -716,7 +716,7 @@ CameraTrigger::Run()
void void
CameraTrigger::engage(void *arg) CameraTrigger::engage(void *arg)
{ {
CameraTrigger *trig = reinterpret_cast<CameraTrigger *>(arg); CameraTrigger *trig = static_cast<CameraTrigger *>(arg);
// Trigger the camera // Trigger the camera
trig->_camera_interface->trigger(true); trig->_camera_interface->trigger(true);
@@ -755,7 +755,7 @@ CameraTrigger::engage(void *arg)
void void
CameraTrigger::disengage(void *arg) CameraTrigger::disengage(void *arg)
{ {
CameraTrigger *trig = reinterpret_cast<CameraTrigger *>(arg); CameraTrigger *trig = static_cast<CameraTrigger *>(arg);
trig->_camera_interface->trigger(false); trig->_camera_interface->trigger(false);
} }
@@ -763,7 +763,7 @@ CameraTrigger::disengage(void *arg)
void void
CameraTrigger::engange_turn_on_off(void *arg) CameraTrigger::engange_turn_on_off(void *arg)
{ {
CameraTrigger *trig = reinterpret_cast<CameraTrigger *>(arg); CameraTrigger *trig = static_cast<CameraTrigger *>(arg);
trig->_camera_interface->send_toggle_power(true); trig->_camera_interface->send_toggle_power(true);
} }
@@ -771,7 +771,7 @@ CameraTrigger::engange_turn_on_off(void *arg)
void void
CameraTrigger::disengage_turn_on_off(void *arg) CameraTrigger::disengage_turn_on_off(void *arg)
{ {
CameraTrigger *trig = reinterpret_cast<CameraTrigger *>(arg); CameraTrigger *trig = static_cast<CameraTrigger *>(arg);
trig->_camera_interface->send_toggle_power(false); trig->_camera_interface->send_toggle_power(false);
} }
@@ -779,7 +779,7 @@ CameraTrigger::disengage_turn_on_off(void *arg)
void void
CameraTrigger::keep_alive_up(void *arg) CameraTrigger::keep_alive_up(void *arg)
{ {
CameraTrigger *trig = reinterpret_cast<CameraTrigger *>(arg); CameraTrigger *trig = static_cast<CameraTrigger *>(arg);
trig->_camera_interface->send_keep_alive(true); trig->_camera_interface->send_keep_alive(true);
} }
@@ -787,7 +787,7 @@ CameraTrigger::keep_alive_up(void *arg)
void void
CameraTrigger::keep_alive_down(void *arg) CameraTrigger::keep_alive_down(void *arg)
{ {
CameraTrigger *trig = reinterpret_cast<CameraTrigger *>(arg); CameraTrigger *trig = static_cast<CameraTrigger *>(arg);
trig->_camera_interface->send_keep_alive(false); trig->_camera_interface->send_keep_alive(false);
} }

View File

@@ -492,7 +492,7 @@ void
DShotOutput::capture_trampoline(void *context, uint32_t chan_index, DShotOutput::capture_trampoline(void *context, uint32_t chan_index,
hrt_abstime edge_time, uint32_t edge_state, uint32_t overflow) hrt_abstime edge_time, uint32_t edge_state, uint32_t overflow)
{ {
DShotOutput *dev = reinterpret_cast<DShotOutput *>(context); DShotOutput *dev = static_cast<DShotOutput *>(context);
dev->capture_callback(chan_index, edge_time, edge_state, overflow); dev->capture_callback(chan_index, edge_time, edge_state, overflow);
} }

View File

@@ -301,7 +301,7 @@ ADIS16477::stop()
int int
ADIS16477::data_ready_interrupt(int irq, void *context, void *arg) ADIS16477::data_ready_interrupt(int irq, void *context, void *arg)
{ {
ADIS16477 *dev = reinterpret_cast<ADIS16477 *>(arg); ADIS16477 *dev = static_cast<ADIS16477 *>(arg);
// make another measurement // make another measurement
dev->ScheduleNow(); dev->ScheduleNow();

View File

@@ -364,7 +364,7 @@ ADIS16497::stop()
int int
ADIS16497::data_ready_interrupt(int irq, void *context, void *arg) ADIS16497::data_ready_interrupt(int irq, void *context, void *arg)
{ {
ADIS16497 *dev = reinterpret_cast<ADIS16497 *>(arg); ADIS16497 *dev = static_cast<ADIS16497 *>(arg);
// make another measurement // make another measurement
dev->ScheduleNow(); dev->ScheduleNow();

View File

@@ -286,7 +286,7 @@ BMI088_gyro::Run()
void void
BMI088_gyro::measure_trampoline(void *arg) BMI088_gyro::measure_trampoline(void *arg)
{ {
BMI088_gyro *dev = reinterpret_cast<BMI088_gyro *>(arg); BMI088_gyro *dev = static_cast<BMI088_gyro *>(arg);
/* make another measurement */ /* make another measurement */
dev->measure(); dev->measure();

View File

@@ -692,7 +692,7 @@ void
PX4FMU::capture_trampoline(void *context, uint32_t chan_index, PX4FMU::capture_trampoline(void *context, uint32_t chan_index,
hrt_abstime edge_time, uint32_t edge_state, uint32_t overflow) hrt_abstime edge_time, uint32_t edge_state, uint32_t overflow)
{ {
PX4FMU *dev = reinterpret_cast<PX4FMU *>(context); PX4FMU *dev = static_cast<PX4FMU *>(context);
dev->capture_callback(chan_index, edge_time, edge_state, overflow); dev->capture_callback(chan_index, edge_time, edge_state, overflow);
} }

View File

@@ -214,7 +214,7 @@ RCInput::cycle_trampoline_init(void *arg)
void void
RCInput::cycle_trampoline(void *arg) RCInput::cycle_trampoline(void *arg)
{ {
RCInput *dev = reinterpret_cast<RCInput *>(arg); RCInput *dev = static_cast<RCInput *>(arg);
dev->cycle(); dev->cycle();
} }

View File

@@ -140,7 +140,7 @@ TEST_PPM::stop()
void void
TEST_PPM::loops(void *arg) TEST_PPM::loops(void *arg)
{ {
TEST_PPM *dev = reinterpret_cast<TEST_PPM *>(arg); TEST_PPM *dev = static_cast<TEST_PPM *>(arg);
dev->do_out(); dev->do_out();
} }
void void

View File

@@ -587,9 +587,9 @@ calibrate_return mag_calibrate_all(orb_advert_t *mavlink_log_pub)
} }
for (size_t cur_mag = 0; cur_mag < orb_mag_count && cur_mag < max_mags; cur_mag++) { for (size_t cur_mag = 0; cur_mag < orb_mag_count && cur_mag < max_mags; cur_mag++) {
worker_data.x[cur_mag] = reinterpret_cast<float *>(malloc(sizeof(float) * calibration_points_maxcount)); worker_data.x[cur_mag] = static_cast<float *>(malloc(sizeof(float) * calibration_points_maxcount));
worker_data.y[cur_mag] = reinterpret_cast<float *>(malloc(sizeof(float) * calibration_points_maxcount)); worker_data.y[cur_mag] = static_cast<float *>(malloc(sizeof(float) * calibration_points_maxcount));
worker_data.z[cur_mag] = reinterpret_cast<float *>(malloc(sizeof(float) * calibration_points_maxcount)); worker_data.z[cur_mag] = static_cast<float *>(malloc(sizeof(float) * calibration_points_maxcount));
if (worker_data.x[cur_mag] == nullptr || worker_data.y[cur_mag] == nullptr || worker_data.z[cur_mag] == nullptr) { if (worker_data.x[cur_mag] == nullptr || worker_data.y[cur_mag] == nullptr || worker_data.z[cur_mag] == nullptr) {
calibration_log_critical(mavlink_log_pub, "ERROR: out of memory"); calibration_log_critical(mavlink_log_pub, "ERROR: out of memory");

View File

@@ -120,7 +120,7 @@ void SendEvent::initialize_trampoline(void *arg)
void SendEvent::cycle_trampoline(void *arg) void SendEvent::cycle_trampoline(void *arg)
{ {
SendEvent *obj = reinterpret_cast<SendEvent *>(arg); SendEvent *obj = static_cast<SendEvent *>(arg);
obj->cycle(); obj->cycle();
} }

View File

@@ -190,7 +190,7 @@ void *LogWriterFile::run_helper(void *context)
{ {
px4_prctl(PR_SET_NAME, "log_writer_file", px4_getpid()); px4_prctl(PR_SET_NAME, "log_writer_file", px4_getpid());
reinterpret_cast<LogWriterFile *>(context)->run(); static_cast<LogWriterFile *>(context)->run();
return nullptr; return nullptr;
} }
@@ -407,7 +407,7 @@ void LogWriterFile::LogFileBuffer::write_no_check(void *ptr, size_t size)
{ {
size_t n = _buffer_size - _head; // bytes to end of the buffer size_t n = _buffer_size - _head; // bytes to end of the buffer
uint8_t *buffer_c = reinterpret_cast<uint8_t *>(ptr); uint8_t *buffer_c = static_cast<uint8_t *>(ptr);
if (size > n) { if (size > n) {
// Message goes over the end of the buffer // Message goes over the end of the buffer