27
27
// POSSIBILITY OF SUCH DAMAGE.
28
28
29
29
30
- #ifndef USB_CAM__USB_CAM_H_
31
- #define USB_CAM__USB_CAM_H_
30
+ #ifndef USB_CAM__USB_CAM_HPP_
31
+ #define USB_CAM__USB_CAM_HPP_
32
+ #include " usb_cam/usb_cam_utils.hpp"
32
33
33
34
#include < asm/types.h> /* for videodev2.h */
34
35
@@ -58,7 +59,8 @@ namespace usb_cam
58
59
{
59
60
60
61
61
- class UsbCam {
62
+ class UsbCam
63
+ {
62
64
public:
63
65
typedef enum
64
66
{
@@ -84,28 +86,28 @@ class UsbCam {
84
86
85
87
// start camera
86
88
bool start (
87
- const std::string& dev, io_method io, pixel_format pf,
89
+ const std::string & dev, io_method io, pixel_format pf,
88
90
int image_width, int image_height, int framerate);
89
91
// shutdown camera
90
92
bool shutdown (void );
91
93
92
94
// grabs a new image from the camera
93
95
// bool get_image(sensor_msgs::msg::Image:::SharedPtr image);
94
- bool get_image (builtin_interfaces::msg::Time& stamp,
95
- std::string& encoding, uint32_t & height, uint32_t & width ,
96
- uint32_t & step, std::vector<uint8_t >& data);
96
+ bool get_image (
97
+ builtin_interfaces::msg::Time & stamp, std::string & encoding ,
98
+ uint32_t & height, uint32_t & width, uint32_t & step, std::vector<uint8_t > & data);
97
99
98
100
void get_formats (); // std::vector<usb_cam::msg::Format>& formats);
99
101
100
102
// enables/disable auto focus
101
103
bool set_auto_focus (int value);
102
104
103
105
// Set video device parameters
104
- bool set_v4l_parameter (const std::string& param, int value);
105
- bool set_v4l_parameter (const std::string& param, const std::string& value);
106
+ bool set_v4l_parameter (const std::string & param, int value);
107
+ bool set_v4l_parameter (const std::string & param, const std::string & value);
106
108
107
- static io_method io_method_from_string (const std::string& str);
108
- static pixel_format pixel_format_from_string (const std::string& str);
109
+ static io_method io_method_from_string (const std::string & str);
110
+ static pixel_format pixel_format_from_string (const std::string & str);
109
111
110
112
bool stop_capturing (void );
111
113
bool start_capturing (void );
@@ -120,7 +122,7 @@ class UsbCam {
120
122
int bytes_per_pixel;
121
123
int image_size;
122
124
builtin_interfaces::msg::Time stamp;
123
- char *image;
125
+ char * image;
124
126
int is_new;
125
127
} camera_image_t ;
126
128
@@ -132,8 +134,8 @@ class UsbCam {
132
134
133
135
134
136
int init_mjpeg_decoder (int image_width, int image_height);
135
- bool mjpeg2rgb (char *MJPEG, int len, char *RGB, int NumPixels);
136
- bool process_image (const void * src, int len, camera_image_t *dest);
137
+ bool mjpeg2rgb (char * MJPEG, int len, char * RGB, int NumPixels);
138
+ bool process_image (const void * src, int len, camera_image_t * dest);
137
139
bool read_frame ();
138
140
bool uninit_device (void );
139
141
bool init_read (unsigned int buffer_size);
@@ -154,17 +156,17 @@ class UsbCam {
154
156
int fd_;
155
157
buffer * buffers_;
156
158
unsigned int n_buffers_;
157
- AVFrame *avframe_camera_;
158
- AVFrame *avframe_rgb_;
159
- AVCodec *avcodec_;
160
- AVDictionary *avoptions_;
161
- AVCodecContext *avcodec_context_;
159
+ AVFrame * avframe_camera_;
160
+ AVFrame * avframe_rgb_;
161
+ AVCodec * avcodec_;
162
+ AVDictionary * avoptions_;
163
+ AVCodecContext * avcodec_context_;
162
164
int avframe_camera_size_;
163
165
int avframe_rgb_size_;
164
- struct SwsContext *video_sws_;
165
- camera_image_t *image_;
166
+ struct SwsContext * video_sws_;
167
+ camera_image_t * image_;
166
168
};
167
169
168
170
} // namespace usb_cam
169
171
170
- #endif // USB_CAM__USB_CAM_H_
172
+ #endif // USB_CAM__USB_CAM_HPP_
0 commit comments