AP_Periph: make constants used in bitshift unisigned

This commit is contained in:
bugobliterator 2022-08-18 05:59:00 +05:30 committed by Andrew Tridgell
parent 3e8355638b
commit 939bd94796
1 changed files with 7 additions and 7 deletions

View File

@ -38,7 +38,7 @@
#include <AP_HAL_SITL/CANSocketIface.h> #include <AP_HAL_SITL/CANSocketIface.h>
#endif #endif
#define IFACE_ALL ((1<<(HAL_NUM_CAN_IFACES+1))-1) #define IFACE_ALL ((1U<<(HAL_NUM_CAN_IFACES+1U))-1U)
#include "i2c.h" #include "i2c.h"
#include <utility> #include <utility>
@ -735,9 +735,9 @@ static void handle_lightscommand(CanardInstance* ins, CanardRxTransfer* transfer
uavcan_equipment_indication_SingleLightCommand &cmd = req.commands.data[i]; uavcan_equipment_indication_SingleLightCommand &cmd = req.commands.data[i];
// to get the right color proportions we scale the green so that is uses the // to get the right color proportions we scale the green so that is uses the
// same number of bits as red and blue // same number of bits as red and blue
uint8_t red = cmd.color.red<<3; uint8_t red = cmd.color.red<<3U;
uint8_t green = (cmd.color.green>>1)<<3; uint8_t green = (cmd.color.green>>1U)<<3U;
uint8_t blue = cmd.color.blue<<3; uint8_t blue = cmd.color.blue<<3U;
#ifdef HAL_PERIPH_ENABLE_NOTIFY #ifdef HAL_PERIPH_ENABLE_NOTIFY
const int8_t brightness = periph.notify.get_rgb_led_brightness_percent(); const int8_t brightness = periph.notify.get_rgb_led_brightness_percent();
#elif defined(AP_PERIPH_HAVE_LED_WITHOUT_NOTIFY) #elif defined(AP_PERIPH_HAVE_LED_WITHOUT_NOTIFY)
@ -1191,7 +1191,7 @@ static void processTx(void)
continue; continue;
} }
#if CANARD_MULTI_IFACE #if CANARD_MULTI_IFACE
if (!(txf->iface_mask & (1<<ins.index))) { if (!(txf->iface_mask & (1U<<ins.index))) {
continue; continue;
} }
#endif #endif
@ -1451,7 +1451,7 @@ static bool can_do_dna()
&allocation_request[0], &allocation_request[0],
(uint16_t) (uid_size + 1) (uint16_t) (uid_size + 1)
#if CANARD_MULTI_IFACE #if CANARD_MULTI_IFACE
,(1 << dronecan.dna_interface) ,(1U << dronecan.dna_interface)
#endif #endif
#if HAL_CANFD_SUPPORTED #if HAL_CANFD_SUPPORTED
,false ,false
@ -2125,7 +2125,7 @@ void AP_Periph_FW::send_moving_baseline_msg()
&buffer[0], &buffer[0],
total_size total_size
#if CANARD_MULTI_IFACE #if CANARD_MULTI_IFACE
,(1<<gps_mb_can_port) ,(1U<<gps_mb_can_port)
#endif #endif
#if HAL_CANFD_SUPPORTED #if HAL_CANFD_SUPPORTED
,canfdout() ,canfdout()