Skip to content

Commit

Permalink
add utils file, fix lint errors
Browse files Browse the repository at this point in the history
  • Loading branch information
flynneva committed Jun 7, 2021
1 parent c4bb6e0 commit 904a088
Show file tree
Hide file tree
Showing 6 changed files with 433 additions and 361 deletions.
7 changes: 3 additions & 4 deletions LICENSE
Original file line number Diff line number Diff line change
@@ -1,8 +1,7 @@
Software License Agreement (BSD License)

Copyright (c) 2014, Robert Bosch LLC.
All rights reserved.

Software License Agreement (BSD License 2.0)

Redistribution and use in source and binary forms, with or without
modification, are permitted provided that the following conditions
are met:
Expand All @@ -13,7 +12,7 @@ are met:
copyright notice, this list of conditions and the following
disclaimer in the documentation and/or other materials provided
with the distribution.
* Neither the name of the Robert Bosch LLC. nor the names of its
* Neither the name of the copyright holder nor the names of its
contributors may be used to endorse or promote products derived
from this software without specific prior written permission.

Expand Down
46 changes: 24 additions & 22 deletions include/usb_cam/usb_cam.h → include/usb_cam/usb_cam.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -27,8 +27,9 @@
// POSSIBILITY OF SUCH DAMAGE.


#ifndef USB_CAM__USB_CAM_H_
#define USB_CAM__USB_CAM_H_
#ifndef USB_CAM__USB_CAM_HPP_
#define USB_CAM__USB_CAM_HPP_
#include "usb_cam/usb_cam_utils.hpp"

#include <asm/types.h> /* for videodev2.h */

Expand Down Expand Up @@ -58,7 +59,8 @@ namespace usb_cam
{


class UsbCam {
class UsbCam
{
public:
typedef enum
{
Expand All @@ -84,28 +86,28 @@ class UsbCam {

// start camera
bool start(
const std::string& dev, io_method io, pixel_format pf,
const std::string & dev, io_method io, pixel_format pf,
int image_width, int image_height, int framerate);
// shutdown camera
bool shutdown(void);

// grabs a new image from the camera
// bool get_image(sensor_msgs::msg::Image:::SharedPtr image);
bool get_image(builtin_interfaces::msg::Time& stamp,
std::string& encoding, uint32_t& height, uint32_t& width,
uint32_t& step, std::vector<uint8_t>& data);
bool get_image(
builtin_interfaces::msg::Time & stamp, std::string & encoding,
uint32_t & height, uint32_t & width, uint32_t & step, std::vector<uint8_t> & data);

void get_formats(); // std::vector<usb_cam::msg::Format>& formats);

// enables/disable auto focus
bool set_auto_focus(int value);

// Set video device parameters
bool set_v4l_parameter(const std::string& param, int value);
bool set_v4l_parameter(const std::string& param, const std::string& value);
bool set_v4l_parameter(const std::string & param, int value);
bool set_v4l_parameter(const std::string & param, const std::string & value);

static io_method io_method_from_string(const std::string& str);
static pixel_format pixel_format_from_string(const std::string& str);
static io_method io_method_from_string(const std::string & str);
static pixel_format pixel_format_from_string(const std::string & str);

bool stop_capturing(void);
bool start_capturing(void);
Expand All @@ -120,7 +122,7 @@ class UsbCam {
int bytes_per_pixel;
int image_size;
builtin_interfaces::msg::Time stamp;
char *image;
char * image;
int is_new;
} camera_image_t;

Expand All @@ -132,8 +134,8 @@ class UsbCam {


int init_mjpeg_decoder(int image_width, int image_height);
bool mjpeg2rgb(char *MJPEG, int len, char *RGB, int NumPixels);
bool process_image(const void * src, int len, camera_image_t *dest);
bool mjpeg2rgb(char * MJPEG, int len, char * RGB, int NumPixels);
bool process_image(const void * src, int len, camera_image_t * dest);
bool read_frame();
bool uninit_device(void);
bool init_read(unsigned int buffer_size);
Expand All @@ -154,17 +156,17 @@ class UsbCam {
int fd_;
buffer * buffers_;
unsigned int n_buffers_;
AVFrame *avframe_camera_;
AVFrame *avframe_rgb_;
AVCodec *avcodec_;
AVDictionary *avoptions_;
AVCodecContext *avcodec_context_;
AVFrame * avframe_camera_;
AVFrame * avframe_rgb_;
AVCodec * avcodec_;
AVDictionary * avoptions_;
AVCodecContext * avcodec_context_;
int avframe_camera_size_;
int avframe_rgb_size_;
struct SwsContext *video_sws_;
camera_image_t *image_;
struct SwsContext * video_sws_;
camera_image_t * image_;
};

} // namespace usb_cam

#endif // USB_CAM__USB_CAM_H_
#endif // USB_CAM__USB_CAM_HPP_
2 changes: 1 addition & 1 deletion include/usb_cam/usb_cam_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@

#ifndef USB_CAM__USB_CAM_NODE_HPP_
#define USB_CAM__USB_CAM_NODE_HPP_
#include "usb_cam/usb_cam.h"
#include "usb_cam/usb_cam.hpp"


#include <rclcpp/rclcpp.hpp>
Expand Down
Loading

0 comments on commit 904a088

Please sign in to comment.