hfl_driver  0.0.20
ROS driver for Continental's HFL110 3D Flash Lidar
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,
73 };
74 
78 class CameraCommander : public nodelet::Nodelet
79 {
80 public:
85 
90 
96  void onInit();
97 
103  bool udpInit();
104 
114  bool createSocket(std::string computerAddr, std::string cameraAddr,
115  uint16_t port, bool isMulticast);
116 
117 private:
119  ros::NodeHandle node_handler_;
120 
122  std::string namespace_;
123 
125  ros::Subscriber frame_data_subscriber_;
126 
128  ros::Subscriber object_data_subscriber_;
129 
131  ros::Subscriber lut_data_subscriber_;
132 
134  ros::ServiceClient udp_send_service_client_;
135 
138 
140  std::shared_ptr<dynamic_reconfigure::Server<hfl_driver::HFLConfig> > dynamic_parameters_server_;
141 
143  ros::Timer timer_;
144 
147 
150 
153 
155  std::string ethernet_interface_;
156 
158  std::string camera_address_;
159 
161  std::string computer_address_;
162 
165 
168 
170  std::shared_ptr<hfl::HflInterface> flash_;
171 
179  void setCommanderState(const ros::TimerEvent& timer_event);
180 
187  bool setFlash();
188 
199  void frameDataCallback(const udp_com::UdpPacket& udp_packet);
200 
211  void objectDataCallback(const udp_com::UdpPacket& udp_packet);
212 
223  void lutDataCallback(const udp_com::UdpPacket& udp_packet);
224 
233  bool sendCommand(const std::vector<uint8_t>& data);
234 
244  void dynamicPametersCallback(hfl_driver::HFLConfig& config, uint32_t level);
245 
250 
256 
257  bool fixError(error_codes error);
258 };
259 
260 } // namespace hfl
261 
262 #endif // CAMERA_COMMANDER__CAMERA_COMMANDER_H_
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