diff --git a/boards/emlid/navio2/navio_sysfs_rc_in/navio_sysfs_rc_in.cpp b/boards/emlid/navio2/navio_sysfs_rc_in/navio_sysfs_rc_in.cpp index 1b5a465805..d42b4b57b4 100644 --- a/boards/emlid/navio2/navio_sysfs_rc_in/navio_sysfs_rc_in.cpp +++ b/boards/emlid/navio2/navio_sysfs_rc_in/navio_sysfs_rc_in.cpp @@ -164,7 +164,7 @@ void RcInput::stop() void RcInput::cycle_trampoline(void *arg) { - RcInput *dev = reinterpret_cast(arg); + RcInput *dev = static_cast(arg); dev->_cycle(); } diff --git a/boards/intel/aerofc-v1/aerofc_adc/aerofc_adc.cpp b/boards/intel/aerofc-v1/aerofc_adc/aerofc_adc.cpp index a84f5eae83..0ae333d1ab 100644 --- a/boards/intel/aerofc-v1/aerofc_adc/aerofc_adc.cpp +++ b/boards/intel/aerofc-v1/aerofc_adc/aerofc_adc.cpp @@ -291,7 +291,7 @@ ssize_t AEROFC_ADC::read(file *filp, char *buffer, size_t len) void AEROFC_ADC::cycle_trampoline(void *arg) { - AEROFC_ADC *dev = reinterpret_cast(arg); + AEROFC_ADC *dev = static_cast(arg); dev->cycle(); } diff --git a/platforms/common/px4_work_queue/ScheduledWorkItem.cpp b/platforms/common/px4_work_queue/ScheduledWorkItem.cpp index 9e96d6c77b..99c4f45e0e 100644 --- a/platforms/common/px4_work_queue/ScheduledWorkItem.cpp +++ b/platforms/common/px4_work_queue/ScheduledWorkItem.cpp @@ -44,7 +44,7 @@ ScheduledWorkItem::~ScheduledWorkItem() void ScheduledWorkItem::schedule_trampoline(void *arg) { - ScheduledWorkItem *dev = reinterpret_cast(arg); + ScheduledWorkItem *dev = static_cast(arg); dev->ScheduleNow(); } diff --git a/platforms/nuttx/src/px4/stm/stm32f4/px4io_serial/px4io_serial.cpp b/platforms/nuttx/src/px4/stm/stm32f4/px4io_serial/px4io_serial.cpp index 8b70c62dc4..e2cf10277d 100644 --- a/platforms/nuttx/src/px4/stm/stm32f4/px4io_serial/px4io_serial.cpp +++ b/platforms/nuttx/src/px4/stm/stm32f4/px4io_serial/px4io_serial.cpp @@ -352,7 +352,7 @@ void ArchPX4IOSerial::_dma_callback(DMA_HANDLE handle, uint8_t status, void *arg) { if (arg != nullptr) { - ArchPX4IOSerial *ps = reinterpret_cast(arg); + ArchPX4IOSerial *ps = static_cast(arg); ps->_do_rx_dma_callback(status); } @@ -387,7 +387,7 @@ int ArchPX4IOSerial::_interrupt(int irq, void *context, void *arg) { if (arg != nullptr) { - ArchPX4IOSerial *instance = reinterpret_cast(arg); + ArchPX4IOSerial *instance = static_cast(arg); instance->_do_interrupt(); } diff --git a/src/drivers/camera_capture/camera_capture.cpp b/src/drivers/camera_capture/camera_capture.cpp index ba65f7c909..19f895e2ca 100644 --- a/src/drivers/camera_capture/camera_capture.cpp +++ b/src/drivers/camera_capture/camera_capture.cpp @@ -88,7 +88,7 @@ CameraCapture::capture_callback(uint32_t chan_index, hrt_abstime edge_time, uint int CameraCapture::gpio_interrupt_routine(int irq, void *context, void *arg) { - CameraCapture *dev = reinterpret_cast(arg); + CameraCapture *dev = static_cast(arg); dev->_trigger.chan_index = 0; dev->_trigger.edge_time = hrt_absolute_time(); @@ -103,7 +103,7 @@ CameraCapture::gpio_interrupt_routine(int irq, void *context, void *arg) void CameraCapture::publish_trigger_trampoline(void *arg) { - CameraCapture *dev = reinterpret_cast(arg); + CameraCapture *dev = static_cast(arg); dev->publish_trigger(); } diff --git a/src/drivers/camera_trigger/camera_trigger.cpp b/src/drivers/camera_trigger/camera_trigger.cpp index d1d892b19a..b8142c21b0 100644 --- a/src/drivers/camera_trigger/camera_trigger.cpp +++ b/src/drivers/camera_trigger/camera_trigger.cpp @@ -716,7 +716,7 @@ CameraTrigger::Run() void CameraTrigger::engage(void *arg) { - CameraTrigger *trig = reinterpret_cast(arg); + CameraTrigger *trig = static_cast(arg); // Trigger the camera trig->_camera_interface->trigger(true); @@ -755,7 +755,7 @@ CameraTrigger::engage(void *arg) void CameraTrigger::disengage(void *arg) { - CameraTrigger *trig = reinterpret_cast(arg); + CameraTrigger *trig = static_cast(arg); trig->_camera_interface->trigger(false); } @@ -763,7 +763,7 @@ CameraTrigger::disengage(void *arg) void CameraTrigger::engange_turn_on_off(void *arg) { - CameraTrigger *trig = reinterpret_cast(arg); + CameraTrigger *trig = static_cast(arg); trig->_camera_interface->send_toggle_power(true); } @@ -771,7 +771,7 @@ CameraTrigger::engange_turn_on_off(void *arg) void CameraTrigger::disengage_turn_on_off(void *arg) { - CameraTrigger *trig = reinterpret_cast(arg); + CameraTrigger *trig = static_cast(arg); trig->_camera_interface->send_toggle_power(false); } @@ -779,7 +779,7 @@ CameraTrigger::disengage_turn_on_off(void *arg) void CameraTrigger::keep_alive_up(void *arg) { - CameraTrigger *trig = reinterpret_cast(arg); + CameraTrigger *trig = static_cast(arg); trig->_camera_interface->send_keep_alive(true); } @@ -787,7 +787,7 @@ CameraTrigger::keep_alive_up(void *arg) void CameraTrigger::keep_alive_down(void *arg) { - CameraTrigger *trig = reinterpret_cast(arg); + CameraTrigger *trig = static_cast(arg); trig->_camera_interface->send_keep_alive(false); } diff --git a/src/drivers/dshot/dshot.cpp b/src/drivers/dshot/dshot.cpp index 98160cd6e7..f0e8c0ad3a 100644 --- a/src/drivers/dshot/dshot.cpp +++ b/src/drivers/dshot/dshot.cpp @@ -492,7 +492,7 @@ void DShotOutput::capture_trampoline(void *context, uint32_t chan_index, hrt_abstime edge_time, uint32_t edge_state, uint32_t overflow) { - DShotOutput *dev = reinterpret_cast(context); + DShotOutput *dev = static_cast(context); dev->capture_callback(chan_index, edge_time, edge_state, overflow); } diff --git a/src/drivers/imu/adis16477/ADIS16477.cpp b/src/drivers/imu/adis16477/ADIS16477.cpp index aa3c36a528..83e08094e6 100644 --- a/src/drivers/imu/adis16477/ADIS16477.cpp +++ b/src/drivers/imu/adis16477/ADIS16477.cpp @@ -301,7 +301,7 @@ ADIS16477::stop() int ADIS16477::data_ready_interrupt(int irq, void *context, void *arg) { - ADIS16477 *dev = reinterpret_cast(arg); + ADIS16477 *dev = static_cast(arg); // make another measurement dev->ScheduleNow(); diff --git a/src/drivers/imu/adis16497/ADIS16497.cpp b/src/drivers/imu/adis16497/ADIS16497.cpp index 60c8200148..824527976c 100644 --- a/src/drivers/imu/adis16497/ADIS16497.cpp +++ b/src/drivers/imu/adis16497/ADIS16497.cpp @@ -364,7 +364,7 @@ ADIS16497::stop() int ADIS16497::data_ready_interrupt(int irq, void *context, void *arg) { - ADIS16497 *dev = reinterpret_cast(arg); + ADIS16497 *dev = static_cast(arg); // make another measurement dev->ScheduleNow(); diff --git a/src/drivers/imu/bmi088/BMI088_gyro.cpp b/src/drivers/imu/bmi088/BMI088_gyro.cpp index 270560d8c2..e040ea3d31 100644 --- a/src/drivers/imu/bmi088/BMI088_gyro.cpp +++ b/src/drivers/imu/bmi088/BMI088_gyro.cpp @@ -286,7 +286,7 @@ BMI088_gyro::Run() void BMI088_gyro::measure_trampoline(void *arg) { - BMI088_gyro *dev = reinterpret_cast(arg); + BMI088_gyro *dev = static_cast(arg); /* make another measurement */ dev->measure(); diff --git a/src/drivers/px4fmu/fmu.cpp b/src/drivers/px4fmu/fmu.cpp index 11d49abcae..5b288a865f 100644 --- a/src/drivers/px4fmu/fmu.cpp +++ b/src/drivers/px4fmu/fmu.cpp @@ -692,7 +692,7 @@ void PX4FMU::capture_trampoline(void *context, uint32_t chan_index, hrt_abstime edge_time, uint32_t edge_state, uint32_t overflow) { - PX4FMU *dev = reinterpret_cast(context); + PX4FMU *dev = static_cast(context); dev->capture_callback(chan_index, edge_time, edge_state, overflow); } diff --git a/src/drivers/rc_input/RCInput.cpp b/src/drivers/rc_input/RCInput.cpp index 2911eda659..208d25fd26 100644 --- a/src/drivers/rc_input/RCInput.cpp +++ b/src/drivers/rc_input/RCInput.cpp @@ -214,7 +214,7 @@ RCInput::cycle_trampoline_init(void *arg) void RCInput::cycle_trampoline(void *arg) { - RCInput *dev = reinterpret_cast(arg); + RCInput *dev = static_cast(arg); dev->cycle(); } diff --git a/src/drivers/test_ppm/test_ppm.cpp b/src/drivers/test_ppm/test_ppm.cpp index de71e5afd1..0e817ef8c9 100644 --- a/src/drivers/test_ppm/test_ppm.cpp +++ b/src/drivers/test_ppm/test_ppm.cpp @@ -140,7 +140,7 @@ TEST_PPM::stop() void TEST_PPM::loops(void *arg) { - TEST_PPM *dev = reinterpret_cast(arg); + TEST_PPM *dev = static_cast(arg); dev->do_out(); } void diff --git a/src/modules/commander/mag_calibration.cpp b/src/modules/commander/mag_calibration.cpp index 966bd87bad..7701de9666 100644 --- a/src/modules/commander/mag_calibration.cpp +++ b/src/modules/commander/mag_calibration.cpp @@ -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++) { - worker_data.x[cur_mag] = reinterpret_cast(malloc(sizeof(float) * calibration_points_maxcount)); - worker_data.y[cur_mag] = reinterpret_cast(malloc(sizeof(float) * calibration_points_maxcount)); - worker_data.z[cur_mag] = reinterpret_cast(malloc(sizeof(float) * calibration_points_maxcount)); + worker_data.x[cur_mag] = static_cast(malloc(sizeof(float) * calibration_points_maxcount)); + worker_data.y[cur_mag] = static_cast(malloc(sizeof(float) * calibration_points_maxcount)); + worker_data.z[cur_mag] = static_cast(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) { calibration_log_critical(mavlink_log_pub, "ERROR: out of memory"); diff --git a/src/modules/events/send_event.cpp b/src/modules/events/send_event.cpp index 1ef9c6589f..6e1143bf8b 100644 --- a/src/modules/events/send_event.cpp +++ b/src/modules/events/send_event.cpp @@ -120,7 +120,7 @@ void SendEvent::initialize_trampoline(void *arg) void SendEvent::cycle_trampoline(void *arg) { - SendEvent *obj = reinterpret_cast(arg); + SendEvent *obj = static_cast(arg); obj->cycle(); } diff --git a/src/modules/logger/log_writer_file.cpp b/src/modules/logger/log_writer_file.cpp index 91dd4560be..05a3ebbe40 100644 --- a/src/modules/logger/log_writer_file.cpp +++ b/src/modules/logger/log_writer_file.cpp @@ -190,7 +190,7 @@ void *LogWriterFile::run_helper(void *context) { px4_prctl(PR_SET_NAME, "log_writer_file", px4_getpid()); - reinterpret_cast(context)->run(); + static_cast(context)->run(); 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 - uint8_t *buffer_c = reinterpret_cast(ptr); + uint8_t *buffer_c = static_cast(ptr); if (size > n) { // Message goes over the end of the buffer