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>
43 #include <nodelet/nodelet.h>
49 #include "udp_com/UdpPacket.h"
50 #include "udp_com/UdpSend.h"
51 #include "udp_com/UdpSocket.h"
114 bool createSocket(std::string computerAddr, std::string cameraAddr,
115 uint16_t port,
bool isMulticast);
170 std::shared_ptr<hfl::HflInterface>
flash_;
233 bool sendCommand(
const std::vector<uint8_t>& data);
Implements the camera configuration and setup.
Definition: camera_commander.h:79
ros::Subscriber frame_data_subscriber_
UDP Frame Data subscriber.
Definition: camera_commander.h:125
std::string computer_address_
IP Address of computer.
Definition: camera_commander.h:161
bool setFlash()
Definition: camera_commander.cpp:173
ros::ServiceClient udp_socket_creation_service_client_
UDP socket service client.
Definition: camera_commander.h:137
ros::Subscriber lut_data_subscriber_
UDP LUT Data Subscriber.
Definition: camera_commander.h:131
bool createSocket(std::string computerAddr, std::string cameraAddr, uint16_t port, bool isMulticast)
Definition: camera_commander.cpp:85
void frameDataCallback(const udp_com::UdpPacket &udp_packet)
Definition: camera_commander.cpp:308
std::shared_ptr< hfl::HflInterface > flash_
Pointer to Flash camera.
Definition: camera_commander.h:170
commander_states previous_state_
Commander Previous state prior to error.
Definition: camera_commander.h:149
commander_states current_state_
Commander current state.
Definition: camera_commander.h:146
void onInit()
Definition: camera_commander.cpp:61
bool udpInit()
Definition: camera_commander.cpp:105
void dynamicPametersCallback(hfl_driver::HFLConfig &config, uint32_t level)
Definition: camera_commander.cpp:377
ros::NodeHandle node_handler_
Node Handle.
Definition: camera_commander.h:119
std::string namespace_
Namespace.
Definition: camera_commander.h:122
std::string camera_address_
IP Address of sensor.
Definition: camera_commander.h:158
bool fixError(error_codes error)
Definition: camera_commander.cpp:290
~CameraCommander()
Definition: camera_commander.cpp:52
ros::Timer timer_
Status checker timer.
Definition: camera_commander.h:143
int object_data_port_
Object Data UDP port.
Definition: camera_commander.h:167
void lutDataCallback(const udp_com::UdpPacket &udp_packet)
error_codes error_status_
Error Status.
Definition: camera_commander.h:152
error_codes checkForError()
Definition: camera_commander.cpp:267
ros::Subscriber object_data_subscriber_
UDP Object Data Subscriber.
Definition: camera_commander.h:128
int frame_data_port_
Frame Data UDP port.
Definition: camera_commander.h:164
void objectDataCallback(const udp_com::UdpPacket &udp_packet)
Definition: camera_commander.cpp:328
bool sendCommand(const std::vector< uint8_t > &data)
Definition: camera_commander.cpp:348
std::string ethernet_interface_
Ethernet Interface.
Definition: camera_commander.h:155
ros::ServiceClient udp_send_service_client_
UDP send service client.
Definition: camera_commander.h:134
CameraCommander()
Definition: camera_commander.cpp:47
void setCommanderState(const ros::TimerEvent &timer_event)
Definition: camera_commander.cpp:208
std::shared_ptr< dynamic_reconfigure::Server< hfl_driver::HFLConfig > > dynamic_parameters_server_
Dynamic Reconfigure server.
Definition: camera_commander.h:140
This file defines the HFL camera's interface class.
Definition: camera_commander.h:56
error_codes
Error Codes.
Definition: camera_commander.h:68
@ object_socket_error
Definition: camera_commander.h:71
@ lut_socket_error
Definition: camera_commander.h:72
@ frame_socket_error
Definition: camera_commander.h:70
@ no_error
Definition: camera_commander.h:69
commander_states
Commander states enum.
Definition: camera_commander.h:59
@ state_done
Definition: camera_commander.h:62
@ state_error
Definition: camera_commander.h:63
@ state_probe
Definition: camera_commander.h:60
@ state_init
Definition: camera_commander.h:61