From 6899c0b5aff211fd2a80c1a63982a5697bed0f0a Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Patrick=20Jos=C3=A9=20Pereira?= Date: Mon, 1 Feb 2021 13:26:28 -0300 Subject: [PATCH] AP_HAL: Add missing const in member functions MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Signed-off-by: Patrick José Pereira --- libraries/AP_HAL/Device.h | 2 +- libraries/AP_HAL/utility/Socket.cpp | 14 +++++++------- libraries/AP_HAL/utility/Socket.h | 14 +++++++------- 3 files changed, 15 insertions(+), 15 deletions(-) diff --git a/libraries/AP_HAL/Device.h b/libraries/AP_HAL/Device.h index 3b6a96a0ae..e37d8cb537 100644 --- a/libraries/AP_HAL/Device.h +++ b/libraries/AP_HAL/Device.h @@ -321,7 +321,7 @@ public: /** * return bus ID with a new devtype */ - uint32_t get_bus_id_devtype(uint8_t devtype) { + uint32_t get_bus_id_devtype(uint8_t devtype) const { return change_bus_id(get_bus_id(), devtype); } diff --git a/libraries/AP_HAL/utility/Socket.cpp b/libraries/AP_HAL/utility/Socket.cpp index cf1530b155..476135abef 100644 --- a/libraries/AP_HAL/utility/Socket.cpp +++ b/libraries/AP_HAL/utility/Socket.cpp @@ -92,7 +92,7 @@ bool SocketAPM::bind(const char *address, uint16_t port) /* set SO_REUSEADDR */ -bool SocketAPM::reuseaddress(void) +bool SocketAPM::reuseaddress(void) const { int one = 1; return (setsockopt(fd, SOL_SOCKET, SO_REUSEADDR, &one, sizeof(one)) != -1); @@ -101,7 +101,7 @@ bool SocketAPM::reuseaddress(void) /* set blocking state */ -bool SocketAPM::set_blocking(bool blocking) +bool SocketAPM::set_blocking(bool blocking) const { int fcntl_ret; if (blocking) { @@ -115,7 +115,7 @@ bool SocketAPM::set_blocking(bool blocking) /* set cloexec state */ -bool SocketAPM::set_cloexec() +bool SocketAPM::set_cloexec() const { return (fcntl(fd, F_SETFD, FD_CLOEXEC) != -1); } @@ -123,7 +123,7 @@ bool SocketAPM::set_cloexec() /* send some data */ -ssize_t SocketAPM::send(const void *buf, size_t size) +ssize_t SocketAPM::send(const void *buf, size_t size) const { return ::send(fd, buf, size, 0); } @@ -153,13 +153,13 @@ ssize_t SocketAPM::recv(void *buf, size_t size, uint32_t timeout_ms) /* return the IP address and port of the last received packet */ -void SocketAPM::last_recv_address(const char *&ip_addr, uint16_t &port) +void SocketAPM::last_recv_address(const char *&ip_addr, uint16_t &port) const { ip_addr = inet_ntoa(in_addr.sin_addr); port = ntohs(in_addr.sin_port); } -void SocketAPM::set_broadcast(void) +void SocketAPM::set_broadcast(void) const { int one = 1; setsockopt(fd,SOL_SOCKET,SO_BROADCAST,(char *)&one,sizeof(one)); @@ -209,7 +209,7 @@ bool SocketAPM::pollout(uint32_t timeout_ms) /* start listening for new tcp connections */ -bool SocketAPM::listen(uint16_t backlog) +bool SocketAPM::listen(uint16_t backlog) const { return ::listen(fd, (int)backlog) == 0; } diff --git a/libraries/AP_HAL/utility/Socket.h b/libraries/AP_HAL/utility/Socket.h index 39b8bd8b35..08a83cc546 100644 --- a/libraries/AP_HAL/utility/Socket.h +++ b/libraries/AP_HAL/utility/Socket.h @@ -37,17 +37,17 @@ public: bool connect(const char *address, uint16_t port); bool bind(const char *address, uint16_t port); - bool reuseaddress(); - bool set_blocking(bool blocking); - bool set_cloexec(); - void set_broadcast(void); + bool reuseaddress() const; + bool set_blocking(bool blocking) const; + bool set_cloexec() const; + void set_broadcast(void) const; - ssize_t send(const void *pkt, size_t size); + ssize_t send(const void *pkt, size_t size) const; ssize_t sendto(const void *buf, size_t size, const char *address, uint16_t port); ssize_t recv(void *pkt, size_t size, uint32_t timeout_ms); // return the IP address and port of the last received packet - void last_recv_address(const char *&ip_addr, uint16_t &port); + void last_recv_address(const char *&ip_addr, uint16_t &port) const; // return true if there is pending data for input bool pollin(uint32_t timeout_ms); @@ -56,7 +56,7 @@ public: bool pollout(uint32_t timeout_ms); // start listening for new tcp connections - bool listen(uint16_t backlog); + bool listen(uint16_t backlog) const; // accept a new connection. Only valid for TCP connections after // listen has been used. A new socket is returned