Implements the camera configuration and setup.
More...
#include <camera_commander.h>
Implements the camera configuration and setup.
◆ CameraCommander()
hfl::CameraCommander::CameraCommander |
( |
| ) |
|
◆ ~CameraCommander()
hfl::CameraCommander::~CameraCommander |
( |
| ) |
|
◆ checkForError()
Checks for Errors and returns the designated error code
◆ createSocket()
bool hfl::CameraCommander::createSocket |
( |
std::string |
computerAddr, |
|
|
std::string |
cameraAddr, |
|
|
uint16_t |
port, |
|
|
bool |
isMulticast |
|
) |
| |
Create Socket Request Function
- Parameters
-
[in] | computerAddr | Computer's IP Address |
[in] | cameraAddr | Camera's IP Address |
[in] | port | UDP port number |
[in] | isMulticast | describes if the connection is multicast |
- Returns
- bool true if socket created
◆ dynamicPametersCallback()
void hfl::CameraCommander::dynamicPametersCallback |
( |
hfl_driver::HFLConfig & |
config, |
|
|
uint32_t |
level |
|
) |
| |
|
private |
Uses the dynamic reconfigure service binded callback dynamic parameter configuration.
- Parameters
-
[in] | config | parameters data |
[in] | level | priority |
- Returns
- void
◆ fixError()
bool hfl::CameraCommander::fixError |
( |
error_codes |
error | ) |
|
|
private |
Fixes the error corresponding to the error code Returns true if error fixed, false otherwise
- Returns
- bool
◆ frameDataCallback()
void hfl::CameraCommander::frameDataCallback |
( |
const udp_com::UdpPacket & |
udp_packet | ) |
|
|
private |
Callback for UDP frame data packets.
Receives the frame data messages for parsing through IP addresses validation.
- Parameters
-
[in] | udp_packet | UDP packet message |
- Returns
- void
◆ lutDataCallback()
void hfl::CameraCommander::lutDataCallback |
( |
const udp_com::UdpPacket & |
udp_packet | ) |
|
|
private |
Callback for UDP LUT data packets
Receives the lut data messages for parsing through IP addresses validation
- Parameters
-
[in] | udp_packet | UDP packet message |
- Returns
- void
◆ objectDataCallback()
void hfl::CameraCommander::objectDataCallback |
( |
const udp_com::UdpPacket & |
udp_packet | ) |
|
|
private |
Callback for UDP object data packets
Receives the object data messages for parsing through IP addresses validation
- Parameters
-
[in] | udp_packet | UDP packet message |
- Returns
- void
◆ onInit()
void hfl::CameraCommander::onInit |
( |
| ) |
|
Initialize Nodelet member variables
- Returns
- void
◆ sendCommand()
bool hfl::CameraCommander::sendCommand |
( |
const std::vector< uint8_t > & |
data | ) |
|
|
private |
Uses the udp_com service binded send function for command sending
- Parameters
-
[in] | data | Data array to be sent |
- Returns
- bool true if command sent succed
◆ setCommanderState()
void hfl::CameraCommander::setCommanderState |
( |
const ros::TimerEvent & |
timer_event | ) |
|
|
private |
Sets CameraCommander current state
- Parameters
-
[in] | timer_event | ROS TimerEvent object |
- Returns
- void
◆ setFlash()
bool hfl::CameraCommander::setFlash |
( |
| ) |
|
|
private |
Loads the HFL camera instace accordingly to the launch parameters
- Returns
- bool true if flash loading succed
◆ udpInit()
bool hfl::CameraCommander::udpInit |
( |
| ) |
|
Initialize UDP topics and services
- Returns
- void
◆ camera_address_
std::string hfl::CameraCommander::camera_address_ |
|
private |
◆ computer_address_
std::string hfl::CameraCommander::computer_address_ |
|
private |
◆ current_state_
◆ dynamic_parameters_server_
std::shared_ptr<dynamic_reconfigure::Server<hfl_driver::HFLConfig> > hfl::CameraCommander::dynamic_parameters_server_ |
|
private |
Dynamic Reconfigure server.
◆ error_status_
◆ ethernet_interface_
std::string hfl::CameraCommander::ethernet_interface_ |
|
private |
◆ flash_
◆ frame_data_port_
int hfl::CameraCommander::frame_data_port_ |
|
private |
◆ frame_data_subscriber_
ros::Subscriber hfl::CameraCommander::frame_data_subscriber_ |
|
private |
UDP Frame Data subscriber.
◆ lut_data_subscriber_
ros::Subscriber hfl::CameraCommander::lut_data_subscriber_ |
|
private |
◆ namespace_
std::string hfl::CameraCommander::namespace_ |
|
private |
◆ node_handler_
ros::NodeHandle hfl::CameraCommander::node_handler_ |
|
private |
◆ object_data_port_
int hfl::CameraCommander::object_data_port_ |
|
private |
◆ object_data_subscriber_
ros::Subscriber hfl::CameraCommander::object_data_subscriber_ |
|
private |
UDP Object Data Subscriber.
◆ previous_state_
Commander Previous state prior to error.
◆ timer_
ros::Timer hfl::CameraCommander::timer_ |
|
private |
◆ udp_send_service_client_
ros::ServiceClient hfl::CameraCommander::udp_send_service_client_ |
|
private |
◆ udp_socket_creation_service_client_
ros::ServiceClient hfl::CameraCommander::udp_socket_creation_service_client_ |
|
private |
UDP socket service client.
The documentation for this class was generated from the following files: