Implements the UDP methods for recieving and sending within the ROS ecosystem.
More...
#include <udp_com.h>
|
void | doReceive () |
|
std::string | getIp () |
| Returns the src IP for the created socket. More...
|
|
size_t | send (const std::vector< u_char > &data, const std::string &ip_address, const uint16_t udp_port) |
|
| UdpCom (std::string computer_address, std::string sensor_address, uint16_t port, bool is_multicast, ros::Publisher publisher) |
|
| ~UdpCom () |
|
Implements the UDP methods for recieving and sending within the ROS ecosystem.
Definition at line 68 of file udp_com.h.
udp_com::UdpCom::UdpCom |
( |
std::string |
computer_address, |
|
|
std::string |
sensor_address, |
|
|
uint16_t |
port, |
|
|
bool |
is_multicast, |
|
|
ros::Publisher |
publisher |
|
) |
| |
Initializer constructor.
- Parameters
-
[in] | computer_address | computer ip address |
[in] | sensor_address | camera ip address |
[in] | port | camera UDP port number |
[in] | is_multicast | multicast flag |
[in] | publisher | ROS publisher |
Definition at line 18 of file udp_com.cpp.
udp_com::UdpCom::~UdpCom |
( |
| ) |
|
void udp_com::UdpCom::doReceive |
( |
| ) |
|
Recieves and publishes the UDP data.
Formats the recieved UDP data and publishes it as a ROS message.
- Returns
- void
Definition at line 89 of file udp_com.cpp.
std::string udp_com::UdpCom::getIp |
( |
| ) |
|
|
inline |
Returns the src IP for the created socket.
Definition at line 113 of file udp_com.h.
size_t udp_com::UdpCom::send |
( |
const std::vector< u_char > & |
data, |
|
|
const std::string & |
ip_address, |
|
|
const uint16_t |
udp_port |
|
) |
| |
Sends data through UDP protocol.
Service send function for UDP data sending.
- Parameters
-
[in] | data | The data to be sent. |
[in] | ip_address | The devide IP address. |
[in] | udp_port | The device port. |
- Returns
- size_t the number of bytes sent
Definition at line 112 of file udp_com.cpp.
std::string udp_com::UdpCom::computer_address_ |
|
private |
Source (computer) IP Address.
Definition at line 141 of file udp_com.h.
boost::asio::io_service udp_com::UdpCom::io_service_ |
|
private |
udp::endpoint udp_com::UdpCom::receiver_endpoint_ |
|
private |
UDP endpoint receiver.
Definition at line 120 of file udp_com.h.
udp::endpoint udp_com::UdpCom::sender_endpoint_ |
|
private |
UDP endpoint sender.
Definition at line 123 of file udp_com.h.
udp::socket udp_com::UdpCom::socket_ |
|
private |
boost::thread udp_com::UdpCom::thread_ |
|
private |
Thread for service.
Definition at line 138 of file udp_com.h.
UdpPacket udp_com::UdpCom::udp_packet_ |
|
private |
UDP packet to be sent.
Definition at line 129 of file udp_com.h.
The documentation for this class was generated from the following files: