hfl_driver  0.0.20
ROS driver for Continental's HFL110 3D Flash Lidar
Public Member Functions | Private Member Functions | Private Attributes | List of all members
hfl::CameraCommander Class Reference

Implements the camera configuration and setup. More...

#include <camera_commander.h>

Inheritance diagram for hfl::CameraCommander:
Inheritance graph
[legend]
Collaboration diagram for hfl::CameraCommander:
Collaboration graph
[legend]

Public Member Functions

 CameraCommander ()
 
 ~CameraCommander ()
 
void onInit ()
 
bool udpInit ()
 
bool createSocket (std::string computerAddr, std::string cameraAddr, uint16_t port, bool isMulticast)
 

Private Member Functions

void setCommanderState (const ros::TimerEvent &timer_event)
 
bool setFlash ()
 
void frameDataCallback (const udp_com::UdpPacket &udp_packet)
 
void objectDataCallback (const udp_com::UdpPacket &udp_packet)
 
void lutDataCallback (const udp_com::UdpPacket &udp_packet)
 
bool sendCommand (const std::vector< uint8_t > &data)
 
void dynamicPametersCallback (hfl_driver::HFLConfig &config, uint32_t level)
 
error_codes checkForError ()
 
bool fixError (error_codes error)
 

Private Attributes

ros::NodeHandle node_handler_
 Node Handle. More...
 
std::string namespace_
 Namespace. More...
 
ros::Subscriber frame_data_subscriber_
 UDP Frame Data subscriber. More...
 
ros::Subscriber object_data_subscriber_
 UDP Object Data Subscriber. More...
 
ros::Subscriber lut_data_subscriber_
 UDP LUT Data Subscriber. More...
 
ros::ServiceClient udp_send_service_client_
 UDP send service client. More...
 
ros::ServiceClient udp_socket_creation_service_client_
 UDP socket service client. More...
 
std::shared_ptr< dynamic_reconfigure::Server< hfl_driver::HFLConfig > > dynamic_parameters_server_
 Dynamic Reconfigure server. More...
 
ros::Timer timer_
 Status checker timer. More...
 
commander_states current_state_
 Commander current state. More...
 
commander_states previous_state_
 Commander Previous state prior to error. More...
 
error_codes error_status_
 Error Status. More...
 
std::string ethernet_interface_
 Ethernet Interface. More...
 
std::string camera_address_
 IP Address of sensor. More...
 
std::string computer_address_
 IP Address of computer. More...
 
int frame_data_port_
 Frame Data UDP port. More...
 
int object_data_port_
 Object Data UDP port. More...
 
std::shared_ptr< hfl::HflInterfaceflash_
 Pointer to Flash camera. More...
 

Detailed Description

Implements the camera configuration and setup.

Constructor & Destructor Documentation

◆ CameraCommander()

hfl::CameraCommander::CameraCommander ( )

CameraCommander constructor

Initialize default variables here

◆ ~CameraCommander()

hfl::CameraCommander::~CameraCommander ( )

CameraCommander destructor

Member Function Documentation

◆ checkForError()

error_codes hfl::CameraCommander::checkForError ( )
private

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]computerAddrComputer's IP Address
[in]cameraAddrCamera's IP Address
[in]portUDP port number
[in]isMulticastdescribes 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]configparameters data
[in]levelpriority
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_packetUDP 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_packetUDP 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_packetUDP 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]dataData 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_eventROS 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

Member Data Documentation

◆ camera_address_

std::string hfl::CameraCommander::camera_address_
private

IP Address of sensor.

◆ computer_address_

std::string hfl::CameraCommander::computer_address_
private

IP Address of computer.

◆ current_state_

commander_states hfl::CameraCommander::current_state_
private

Commander 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_

error_codes hfl::CameraCommander::error_status_
private

Error Status.

◆ ethernet_interface_

std::string hfl::CameraCommander::ethernet_interface_
private

Ethernet Interface.

◆ flash_

std::shared_ptr<hfl::HflInterface> hfl::CameraCommander::flash_
private

Pointer to Flash camera.

◆ frame_data_port_

int hfl::CameraCommander::frame_data_port_
private

Frame Data UDP port.

◆ 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

UDP LUT Data Subscriber.

◆ namespace_

std::string hfl::CameraCommander::namespace_
private

Namespace.

◆ node_handler_

ros::NodeHandle hfl::CameraCommander::node_handler_
private

Node Handle.

◆ object_data_port_

int hfl::CameraCommander::object_data_port_
private

Object Data UDP port.

◆ object_data_subscriber_

ros::Subscriber hfl::CameraCommander::object_data_subscriber_
private

UDP Object Data Subscriber.

◆ previous_state_

commander_states hfl::CameraCommander::previous_state_
private

Commander Previous state prior to error.

◆ timer_

ros::Timer hfl::CameraCommander::timer_
private

Status checker timer.

◆ udp_send_service_client_

ros::ServiceClient hfl::CameraCommander::udp_send_service_client_
private

UDP send service client.

◆ 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: