Go to the documentation of this file.
36 #ifndef CAMERA_COMMANDER__CAMERA_COMMANDER_H_
37 #define CAMERA_COMMANDER__CAMERA_COMMANDER_H_
39 #include <hfl_driver/HFLConfig.h>
42 #include <dynamic_reconfigure/server.h>
49 #include "udp_com/UdpPacket.h"
50 #include "udp_com/UdpSend.h"
51 #include "udp_com/UdpSocket.h"
116 bool createSocket(std::string computerAddr, std::string cameraAddr,
117 uint16_t port,
bool isMulticast);
187 std::shared_ptr<hfl::HflInterface>
flash_;
274 bool sendCommand(
const std::vector<uint8_t>& data);
303 #endif // CAMERA_COMMANDER__CAMERA_COMMANDER_H_
std::shared_ptr< hfl::HflInterface > flash_
Pointer to Flash camera.
int slice_data_port_
Slice Data UDP port.
void teleDataCallback(const udp_com::UdpPacket &udp_packet)
ros::Subscriber pdm_data_subscriber_
UDP PDM Data Subscriber.
ros::Subscriber object_data_subscriber_
UDP Object Data Subscriber.
error_codes error_status_
Error Status.
void objectDataCallback(const udp_com::UdpPacket &udp_packet)
std::shared_ptr< dynamic_reconfigure::Server< hfl_driver::HFLConfig > > dynamic_parameters_server_
Dynamic Reconfigure server.
void dynamicPametersCallback(hfl_driver::HFLConfig &config, uint32_t level)
error_codes checkForError()
int tele_data_port_
Telemetry Data UDP port.
int pdm_data_port_
PDM Data UDP port.
void pdmDataCallback(const udp_com::UdpPacket &udp_packet)
std::string ethernet_interface_
Ethernet Interface.
std::string namespace_
Namespace.
ros::Subscriber slice_data_subscriber_
UDP Slice Data Subscriber.
commander_states
Commander states enum.
ros::Timer timer_
Status checker timer.
commander_states current_state_
Commander current state.
This file defines the HFL camera's interface class.
void sliceDataCallback(const udp_com::UdpPacket &udp_packet)
ros::Subscriber frame_data_subscriber_
UDP Frame Data subscriber.
void setCommanderState(const ros::TimerEvent &timer_event)
bool sendCommand(const std::vector< uint8_t > &data)
int object_data_port_
Object Data UDP port.
bool createSocket(std::string computerAddr, std::string cameraAddr, uint16_t port, bool isMulticast)
commander_states previous_state_
Commander Previous state prior to error.
std::string computer_address_
IP Address of computer.
ros::ServiceClient udp_socket_creation_service_client_
UDP socket service client.
int frame_data_port_
Frame Data UDP port.
std::string camera_address_
IP Address of sensor.
Implements the camera configuration and setup.
ros::ServiceClient udp_send_service_client_
UDP send service client.
void frameDataCallback(const udp_com::UdpPacket &udp_packet)
ros::NodeHandle node_handler_
Node Handle.
ros::Subscriber tele_data_subscriber_
UDP Telemetry Data Subscriber.
bool fixError(error_codes error)
hfl_driver
Author(s): Evan Flynn
, Maxton Ginier , Gerardo Bravo , Moises Diaz
autogenerated on Wed Mar 2 2022 00:22:32