mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-30 12:38:33 -04:00
AP_HAL: Add missing const in member functions
Signed-off-by: Patrick José Pereira <patrickelectric@gmail.com>
This commit is contained in:
parent
98a8e6e370
commit
6899c0b5af
@ -321,7 +321,7 @@ public:
|
|||||||
/**
|
/**
|
||||||
* return bus ID with a new devtype
|
* 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);
|
return change_bus_id(get_bus_id(), devtype);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -92,7 +92,7 @@ bool SocketAPM::bind(const char *address, uint16_t port)
|
|||||||
/*
|
/*
|
||||||
set SO_REUSEADDR
|
set SO_REUSEADDR
|
||||||
*/
|
*/
|
||||||
bool SocketAPM::reuseaddress(void)
|
bool SocketAPM::reuseaddress(void) const
|
||||||
{
|
{
|
||||||
int one = 1;
|
int one = 1;
|
||||||
return (setsockopt(fd, SOL_SOCKET, SO_REUSEADDR, &one, sizeof(one)) != -1);
|
return (setsockopt(fd, SOL_SOCKET, SO_REUSEADDR, &one, sizeof(one)) != -1);
|
||||||
@ -101,7 +101,7 @@ bool SocketAPM::reuseaddress(void)
|
|||||||
/*
|
/*
|
||||||
set blocking state
|
set blocking state
|
||||||
*/
|
*/
|
||||||
bool SocketAPM::set_blocking(bool blocking)
|
bool SocketAPM::set_blocking(bool blocking) const
|
||||||
{
|
{
|
||||||
int fcntl_ret;
|
int fcntl_ret;
|
||||||
if (blocking) {
|
if (blocking) {
|
||||||
@ -115,7 +115,7 @@ bool SocketAPM::set_blocking(bool blocking)
|
|||||||
/*
|
/*
|
||||||
set cloexec state
|
set cloexec state
|
||||||
*/
|
*/
|
||||||
bool SocketAPM::set_cloexec()
|
bool SocketAPM::set_cloexec() const
|
||||||
{
|
{
|
||||||
return (fcntl(fd, F_SETFD, FD_CLOEXEC) != -1);
|
return (fcntl(fd, F_SETFD, FD_CLOEXEC) != -1);
|
||||||
}
|
}
|
||||||
@ -123,7 +123,7 @@ bool SocketAPM::set_cloexec()
|
|||||||
/*
|
/*
|
||||||
send some data
|
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);
|
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
|
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);
|
ip_addr = inet_ntoa(in_addr.sin_addr);
|
||||||
port = ntohs(in_addr.sin_port);
|
port = ntohs(in_addr.sin_port);
|
||||||
}
|
}
|
||||||
|
|
||||||
void SocketAPM::set_broadcast(void)
|
void SocketAPM::set_broadcast(void) const
|
||||||
{
|
{
|
||||||
int one = 1;
|
int one = 1;
|
||||||
setsockopt(fd,SOL_SOCKET,SO_BROADCAST,(char *)&one,sizeof(one));
|
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
|
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;
|
return ::listen(fd, (int)backlog) == 0;
|
||||||
}
|
}
|
||||||
|
@ -37,17 +37,17 @@ public:
|
|||||||
|
|
||||||
bool connect(const char *address, uint16_t port);
|
bool connect(const char *address, uint16_t port);
|
||||||
bool bind(const char *address, uint16_t port);
|
bool bind(const char *address, uint16_t port);
|
||||||
bool reuseaddress();
|
bool reuseaddress() const;
|
||||||
bool set_blocking(bool blocking);
|
bool set_blocking(bool blocking) const;
|
||||||
bool set_cloexec();
|
bool set_cloexec() const;
|
||||||
void set_broadcast(void);
|
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 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);
|
ssize_t recv(void *pkt, size_t size, uint32_t timeout_ms);
|
||||||
|
|
||||||
// return the IP address and port of the last received packet
|
// 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
|
// return true if there is pending data for input
|
||||||
bool pollin(uint32_t timeout_ms);
|
bool pollin(uint32_t timeout_ms);
|
||||||
@ -56,7 +56,7 @@ public:
|
|||||||
bool pollout(uint32_t timeout_ms);
|
bool pollout(uint32_t timeout_ms);
|
||||||
|
|
||||||
// start listening for new tcp connections
|
// 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
|
// accept a new connection. Only valid for TCP connections after
|
||||||
// listen has been used. A new socket is returned
|
// listen has been used. A new socket is returned
|
||||||
|
Loading…
Reference in New Issue
Block a user