camera_commander.h
Go to the documentation of this file.
1 // Copyright 2020 Continental AG
2 // All rights reserved.
3 //
4 // Software License Agreement (BSD 2-Clause Simplified License)
5 //
6 // Redistribution and use in source and binary forms, with or without
7 // modification, are permitted provided that the following conditions
8 // are met:
9 //
10 // * Redistributions of source code must retain the above copyright
11 // notice, this list of conditions and the following disclaimer.
12 // * Redistributions in binary form must reproduce the above
13 // copyright notice, this list of conditions and the following
14 // disclaimer in the documentation and/or other materials provided
15 // with the distribution.
16 //
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
18 // "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
19 // LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
20 // FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
21 // COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
22 // INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
23 // BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
24 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
25 // CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
26 // LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
27 // ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
28 // POSSIBILITY OF SUCH DAMAGE.
29 
30 
36 #ifndef CAMERA_COMMANDER__CAMERA_COMMANDER_H_
37 #define CAMERA_COMMANDER__CAMERA_COMMANDER_H_
38 
39 #include <hfl_driver/HFLConfig.h>
40 #include <hfl_interface.h>
41 
42 #include <dynamic_reconfigure/server.h>
43 #include <nodelet/nodelet.h>
44 
45 #include <vector>
46 #include <string>
47 #include <memory>
48 
49 #include "udp_com/UdpPacket.h"
50 #include "udp_com/UdpSend.h"
51 #include "udp_com/UdpSocket.h"
52 
53 #include "ros/ros.h"
54 
55 namespace hfl
56 {
59 {
64 };
65 
68 {
69  no_error = 0,
75 };
76 
81 {
82 public:
87 
92 
98  void onInit();
99 
105  bool udpInit();
106 
116  bool createSocket(std::string computerAddr, std::string cameraAddr,
117  uint16_t port, bool isMulticast);
118 
119 private:
122 
124  std::string namespace_;
125 
128 
131 
134 
137 
140 
143 
146 
148  std::shared_ptr<dynamic_reconfigure::Server<hfl_driver::HFLConfig> > dynamic_parameters_server_;
149 
152 
155 
158 
161 
163  std::string ethernet_interface_;
164 
166  std::string camera_address_;
167 
169  std::string computer_address_;
170 
173 
176 
179 
182 
185 
187  std::shared_ptr<hfl::HflInterface> flash_;
188 
196  void setCommanderState(const ros::TimerEvent& timer_event);
197 
204  bool setFlash();
205 
216  void frameDataCallback(const udp_com::UdpPacket& udp_packet);
217 
228  void pdmDataCallback(const udp_com::UdpPacket& udp_packet);
229 
240  void objectDataCallback(const udp_com::UdpPacket& udp_packet);
241 
252  void teleDataCallback(const udp_com::UdpPacket& udp_packet);
253 
264  void sliceDataCallback(const udp_com::UdpPacket& udp_packet);
265 
274  bool sendCommand(const std::vector<uint8_t>& data);
275 
285  void dynamicPametersCallback(hfl_driver::HFLConfig& config, uint32_t level);
286 
291 
297 
298  bool fixError(error_codes error);
299 };
300 
301 } // namespace hfl
302 
303 #endif // CAMERA_COMMANDER__CAMERA_COMMANDER_H_
hfl::CameraCommander::flash_
std::shared_ptr< hfl::HflInterface > flash_
Pointer to Flash camera.
Definition: camera_commander.h:187
hfl::frame_socket_error
@ frame_socket_error
Definition: camera_commander.h:70
hfl::CameraCommander::slice_data_port_
int slice_data_port_
Slice Data UDP port.
Definition: camera_commander.h:184
hfl::state_done
@ state_done
Definition: camera_commander.h:62
hfl::CameraCommander::teleDataCallback
void teleDataCallback(const udp_com::UdpPacket &udp_packet)
Definition: camera_commander.cpp:427
hfl::CameraCommander::~CameraCommander
~CameraCommander()
Definition: camera_commander.cpp:52
hfl::tele_socket_error
@ tele_socket_error
Definition: camera_commander.h:73
hfl::CameraCommander::pdm_data_subscriber_
ros::Subscriber pdm_data_subscriber_
UDP PDM Data Subscriber.
Definition: camera_commander.h:130
hfl::CameraCommander::onInit
void onInit()
Definition: camera_commander.cpp:61
hfl::CameraCommander::CameraCommander
CameraCommander()
Definition: camera_commander.cpp:47
hfl::CameraCommander::object_data_subscriber_
ros::Subscriber object_data_subscriber_
UDP Object Data Subscriber.
Definition: camera_commander.h:133
hfl::no_error
@ no_error
Definition: camera_commander.h:69
hfl::CameraCommander::error_status_
error_codes error_status_
Error Status.
Definition: camera_commander.h:160
hfl::CameraCommander::objectDataCallback
void objectDataCallback(const udp_com::UdpPacket &udp_packet)
Definition: camera_commander.cpp:407
ros.h
hfl::CameraCommander::dynamic_parameters_server_
std::shared_ptr< dynamic_reconfigure::Server< hfl_driver::HFLConfig > > dynamic_parameters_server_
Dynamic Reconfigure server.
Definition: camera_commander.h:148
hfl
Definition: base_hfl110dcu.h:42
hfl::CameraCommander::dynamicPametersCallback
void dynamicPametersCallback(hfl_driver::HFLConfig &config, uint32_t level)
Definition: camera_commander.cpp:496
hfl::CameraCommander::checkForError
error_codes checkForError()
Definition: camera_commander.cpp:315
hfl::CameraCommander::tele_data_port_
int tele_data_port_
Telemetry Data UDP port.
Definition: camera_commander.h:181
hfl::object_socket_error
@ object_socket_error
Definition: camera_commander.h:72
hfl::CameraCommander::pdm_data_port_
int pdm_data_port_
PDM Data UDP port.
Definition: camera_commander.h:175
hfl::state_probe
@ state_probe
Definition: camera_commander.h:60
hfl::CameraCommander::udpInit
bool udpInit()
Definition: camera_commander.cpp:105
hfl::CameraCommander::pdmDataCallback
void pdmDataCallback(const udp_com::UdpPacket &udp_packet)
Definition: camera_commander.cpp:387
hfl::CameraCommander::ethernet_interface_
std::string ethernet_interface_
Ethernet Interface.
Definition: camera_commander.h:163
hfl::CameraCommander::namespace_
std::string namespace_
Namespace.
Definition: camera_commander.h:124
hfl::CameraCommander::slice_data_subscriber_
ros::Subscriber slice_data_subscriber_
UDP Slice Data Subscriber.
Definition: camera_commander.h:139
hfl::commander_states
commander_states
Commander states enum.
Definition: camera_commander.h:58
hfl::CameraCommander::timer_
ros::Timer timer_
Status checker timer.
Definition: camera_commander.h:151
hfl::CameraCommander::current_state_
commander_states current_state_
Commander current state.
Definition: camera_commander.h:154
hfl_interface.h
This file defines the HFL camera's interface class.
hfl::CameraCommander::sliceDataCallback
void sliceDataCallback(const udp_com::UdpPacket &udp_packet)
Definition: camera_commander.cpp:447
ros::ServiceClient
hfl::state_init
@ state_init
Definition: camera_commander.h:61
hfl::CameraCommander::frame_data_subscriber_
ros::Subscriber frame_data_subscriber_
UDP Frame Data subscriber.
Definition: camera_commander.h:127
ros::TimerEvent
hfl::CameraCommander::setCommanderState
void setCommanderState(const ros::TimerEvent &timer_event)
Definition: camera_commander.cpp:256
hfl::CameraCommander::sendCommand
bool sendCommand(const std::vector< uint8_t > &data)
Definition: camera_commander.cpp:467
hfl::CameraCommander::object_data_port_
int object_data_port_
Object Data UDP port.
Definition: camera_commander.h:178
hfl::CameraCommander::createSocket
bool createSocket(std::string computerAddr, std::string cameraAddr, uint16_t port, bool isMulticast)
Definition: camera_commander.cpp:85
nodelet::Nodelet
hfl::CameraCommander::previous_state_
commander_states previous_state_
Commander Previous state prior to error.
Definition: camera_commander.h:157
hfl::error_codes
error_codes
Error Codes.
Definition: camera_commander.h:67
nodelet.h
hfl::CameraCommander::computer_address_
std::string computer_address_
IP Address of computer.
Definition: camera_commander.h:169
hfl::CameraCommander::udp_socket_creation_service_client_
ros::ServiceClient udp_socket_creation_service_client_
UDP socket service client.
Definition: camera_commander.h:145
hfl::CameraCommander::frame_data_port_
int frame_data_port_
Frame Data UDP port.
Definition: camera_commander.h:172
hfl::CameraCommander::camera_address_
std::string camera_address_
IP Address of sensor.
Definition: camera_commander.h:166
hfl::CameraCommander
Implements the camera configuration and setup.
Definition: camera_commander.h:80
hfl::CameraCommander::udp_send_service_client_
ros::ServiceClient udp_send_service_client_
UDP send service client.
Definition: camera_commander.h:142
hfl::CameraCommander::frameDataCallback
void frameDataCallback(const udp_com::UdpPacket &udp_packet)
Definition: camera_commander.cpp:367
hfl::pdm_socket_error
@ pdm_socket_error
Definition: camera_commander.h:71
hfl::state_error
@ state_error
Definition: camera_commander.h:63
ros::Timer
hfl::CameraCommander::setFlash
bool setFlash()
Definition: camera_commander.cpp:221
hfl::CameraCommander::node_handler_
ros::NodeHandle node_handler_
Node Handle.
Definition: camera_commander.h:121
ros::NodeHandle
ros::Subscriber
hfl::CameraCommander::tele_data_subscriber_
ros::Subscriber tele_data_subscriber_
UDP Telemetry Data Subscriber.
Definition: camera_commander.h:136
hfl::CameraCommander::fixError
bool fixError(error_codes error)
Definition: camera_commander.cpp:349
hfl::slice_socket_error
@ slice_socket_error
Definition: camera_commander.h:74


hfl_driver
Author(s): Evan Flynn , Maxton Ginier , Gerardo Bravo , Moises Diaz
autogenerated on Wed Mar 2 2022 00:22:32