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]

Public Member Functions

 CameraCommander ()
 
bool createSocket (std::string computerAddr, std::string cameraAddr, uint16_t port, bool isMulticast)
 
void onInit ()
 
bool udpInit ()
 
 ~CameraCommander ()
 
- Public Member Functions inherited from nodelet::Nodelet
void init (const std::string &name, const M_string &remapping_args, const V_string &my_argv, ros::CallbackQueueInterface *st_queue=NULL, ros::CallbackQueueInterface *mt_queue=NULL)
 
 Nodelet ()
 
virtual ~Nodelet ()
 

Private Member Functions

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

Private Attributes

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

Additional Inherited Members

- Protected Member Functions inherited from nodelet::Nodelet
ros::CallbackQueueInterfacegetMTCallbackQueue () const
 
ros::NodeHandlegetMTNodeHandle () const
 
ros::NodeHandlegetMTPrivateNodeHandle () const
 
const V_stringgetMyArgv () const
 
const std::string & getName () const
 
ros::NodeHandlegetNodeHandle () const
 
ros::NodeHandlegetPrivateNodeHandle () const
 
const M_stringgetRemappingArgs () const
 
ros::CallbackQueueInterfacegetSTCallbackQueue () const
 
std::string getSuffixedName (const std::string &suffix) const
 

Detailed Description

Implements the camera configuration and setup.

Definition at line 80 of file camera_commander.h.

Constructor & Destructor Documentation

hfl::CameraCommander::CameraCommander ( )

CameraCommander constructor

Initialize default variables here

Definition at line 47 of file camera_commander.cpp.

hfl::CameraCommander::~CameraCommander ( )

CameraCommander destructor

Definition at line 52 of file camera_commander.cpp.

Member Function Documentation

error_codes hfl::CameraCommander::checkForError ( )
private

Checks for Errors and returns the designated error code

Definition at line 315 of file camera_commander.cpp.

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

Definition at line 85 of file camera_commander.cpp.

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

Definition at line 496 of file camera_commander.cpp.

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

Definition at line 349 of file camera_commander.cpp.

void hfl::CameraCommander::frameDataCallback ( const udp_com::UdpPacket &  udp_packet)
private

Callback for frame data UDP packets.

Receives the frame data messages for parsing through IP addresses validation.

Parameters
[in]udp_packetUDP packet message
Returns
void

Definition at line 367 of file camera_commander.cpp.

void hfl::CameraCommander::objectDataCallback ( const udp_com::UdpPacket &  udp_packet)
private

Callback for object data UDP packets

Receives the object data messages for parsing through IP addresses validation

Parameters
[in]udp_packetUDP packet message
Returns
void

Definition at line 407 of file camera_commander.cpp.

void hfl::CameraCommander::onInit ( )
virtual

Initialize Nodelet member variables

Returns
void

Implements nodelet::Nodelet.

Definition at line 61 of file camera_commander.cpp.

void hfl::CameraCommander::pdmDataCallback ( const udp_com::UdpPacket &  udp_packet)
private

Callback for performance degredation module (PDM) data UDP packets

Receives the PDM data messages for parsing through IP addresses validation

Parameters
[in]udp_packetUDP packet message
Returns
void

Definition at line 387 of file camera_commander.cpp.

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

Definition at line 467 of file camera_commander.cpp.

void hfl::CameraCommander::setCommanderState ( const ros::TimerEvent timer_event)
private

Sets CameraCommander current state

Parameters
[in]timer_eventROS TimerEvent object
Returns
void

Definition at line 256 of file camera_commander.cpp.

bool hfl::CameraCommander::setFlash ( )
private

Loads the HFL camera instace accordingly to the launch parameters

Returns
bool true if flash loading succed

Definition at line 221 of file camera_commander.cpp.

void hfl::CameraCommander::sliceDataCallback ( const udp_com::UdpPacket &  udp_packet)
private

Callback for slice data UDP packets

Receives the slice data messages for parsing through IP addresses validation

Parameters
[in]udp_packetUDP packet message
Returns
void

Definition at line 447 of file camera_commander.cpp.

void hfl::CameraCommander::teleDataCallback ( const udp_com::UdpPacket &  udp_packet)
private

Callback for telemetry data UDP packets

Receives the telemetry data messages for parsing through IP addresses validation

Parameters
[in]udp_packetUDP packet message
Returns
void

Definition at line 427 of file camera_commander.cpp.

bool hfl::CameraCommander::udpInit ( )

Initialize UDP topics and services

Returns
void

Definition at line 105 of file camera_commander.cpp.

Member Data Documentation

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

IP Address of sensor.

Definition at line 166 of file camera_commander.h.

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

IP Address of computer.

Definition at line 169 of file camera_commander.h.

commander_states hfl::CameraCommander::current_state_
private

Commander current state.

Definition at line 154 of file camera_commander.h.

std::shared_ptr<dynamic_reconfigure::Server<hfl_driver::HFLConfig> > hfl::CameraCommander::dynamic_parameters_server_
private

Dynamic Reconfigure server.

Definition at line 148 of file camera_commander.h.

error_codes hfl::CameraCommander::error_status_
private

Error Status.

Definition at line 160 of file camera_commander.h.

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

Ethernet Interface.

Definition at line 163 of file camera_commander.h.

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

Pointer to Flash camera.

Definition at line 187 of file camera_commander.h.

int hfl::CameraCommander::frame_data_port_
private

Frame Data UDP port.

Definition at line 172 of file camera_commander.h.

ros::Subscriber hfl::CameraCommander::frame_data_subscriber_
private

UDP Frame Data subscriber.

Definition at line 127 of file camera_commander.h.

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

Namespace.

Definition at line 124 of file camera_commander.h.

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

Node Handle.

Definition at line 121 of file camera_commander.h.

int hfl::CameraCommander::object_data_port_
private

Object Data UDP port.

Definition at line 178 of file camera_commander.h.

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

UDP Object Data Subscriber.

Definition at line 133 of file camera_commander.h.

int hfl::CameraCommander::pdm_data_port_
private

PDM Data UDP port.

Definition at line 175 of file camera_commander.h.

ros::Subscriber hfl::CameraCommander::pdm_data_subscriber_
private

UDP PDM Data Subscriber.

Definition at line 130 of file camera_commander.h.

commander_states hfl::CameraCommander::previous_state_
private

Commander Previous state prior to error.

Definition at line 157 of file camera_commander.h.

int hfl::CameraCommander::slice_data_port_
private

Slice Data UDP port.

Definition at line 184 of file camera_commander.h.

ros::Subscriber hfl::CameraCommander::slice_data_subscriber_
private

UDP Slice Data Subscriber.

Definition at line 139 of file camera_commander.h.

int hfl::CameraCommander::tele_data_port_
private

Telemetry Data UDP port.

Definition at line 181 of file camera_commander.h.

ros::Subscriber hfl::CameraCommander::tele_data_subscriber_
private

UDP Telemetry Data Subscriber.

Definition at line 136 of file camera_commander.h.

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

Status checker timer.

Definition at line 151 of file camera_commander.h.

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

UDP send service client.

Definition at line 142 of file camera_commander.h.

ros::ServiceClient hfl::CameraCommander::udp_socket_creation_service_client_
private

UDP socket service client.

Definition at line 145 of file camera_commander.h.


The documentation for this class was generated from the following files:


hfl_driver
Author(s): Evan Flynn , Maxton Ginier , Gerardo Bravo , Moises Diaz
autogenerated on Sat Mar 20 2021 02:27:31