Skip to content

Commit

Permalink
use the v4l2_buffer timestamp if available. #75
Browse files Browse the repository at this point in the history
usb_cam.cpp is building but untested #103

Builds but crashes immediately after running

data is getting published, no image shown

image shown, frame rate is very slow #103
  • Loading branch information
lucasw authored and flynneva committed Mar 24, 2021
1 parent ddc19f2 commit 966ad3d
Show file tree
Hide file tree
Showing 8 changed files with 505 additions and 246 deletions.
5 changes: 5 additions & 0 deletions CHANGELOG.rst
Original file line number Diff line number Diff line change
Expand Up @@ -2,6 +2,11 @@
Changelog for package usb_cam
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^

0.3.7 (2018-10-29)
------------------

* ROS2 version

0.3.6 (2017-06-15)
------------------
* .travis.yml: udpate to trusty
Expand Down
60 changes: 22 additions & 38 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,34 +1,24 @@
cmake_minimum_required(VERSION 2.8.3)
cmake_minimum_required(VERSION 3.5)
project(usb_cam)

## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages
find_package(catkin REQUIRED COMPONENTS image_transport roscpp std_msgs std_srvs sensor_msgs camera_info_manager)

# find_package(camera_info_manager REQUIRED)
# find_package(image_transport REQUIRED)
find_package(builtin_interfaces REQUIRED)
find_package(rclcpp REQUIRED)
find_package(std_msgs REQUIRED)
find_package(std_srvs REQUIRED)
find_package(sensor_msgs REQUIRED)

## pkg-config libraries
find_package(PkgConfig REQUIRED)
pkg_check_modules(avcodec libavcodec REQUIRED)
pkg_check_modules(swscale libswscale REQUIRED)

###################################################
## Declare things to be passed to other projects ##
###################################################

## LIBRARIES: libraries you create in this project that dependent projects also need
## CATKIN_DEPENDS: catkin_packages dependent projects also need
## DEPENDS: system dependencies of this project that dependent projects also need
catkin_package(
INCLUDE_DIRS include
LIBRARIES ${PROJECT_NAME}
)

###########
## Build ##
###########

include_directories(include
${catkin_INCLUDE_DIRS}
${avcodec_INCLUDE_DIRS}
${swscale_INCLUDE_DIRS}
)
Expand All @@ -38,7 +28,6 @@ add_library(${PROJECT_NAME} src/usb_cam.cpp)
target_link_libraries(${PROJECT_NAME}
${avcodec_LIBRARIES}
${swscale_LIBRARIES}
${catkin_LIBRARIES}
)

## Declare a cpp executable
Expand All @@ -47,26 +36,21 @@ target_link_libraries(${PROJECT_NAME}_node
${PROJECT_NAME}
${avcodec_LIBRARIES}
${swscale_LIBRARIES}
${catkin_LIBRARIES}
# TODO(lucasw) should this have been in libavcodec?
avutil
)

#############
## Install ##
#############

## Mark executables and/or libraries for installation
install(TARGETS ${PROJECT_NAME}_node ${PROJECT_NAME}
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
ament_target_dependencies(${PROJECT_NAME}
"builtin_interfaces"
"rclcpp"
"sensor_msgs"
"std_msgs"
"std_srvs"
)

## Copy launch files
install(DIRECTORY launch/
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch
FILES_MATCHING PATTERN "*.launch"
)
install(TARGETS ${PROJECT_NAME} ${PROJECT_NAME}_node DESTINATION lib/${PROJECT_NAME})
install(PROGRAMS scripts/show_image.py DESTINATION lib/${PROJECT_NAME})

install(DIRECTORY include/${PROJECT_NAME}/
DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
FILES_MATCHING PATTERN "*.h" PATTERN "*.hpp"
)
install(DIRECTORY launch DESTINATION share/${PROJECT_NAME})

ament_package()
4 changes: 2 additions & 2 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,10 +1,10 @@
usb_cam [![Build Status](https://api.travis-ci.org/bosch-ros-pkg/usb_cam.png)](https://travis-ci.org/bosch-ros-pkg/usb_cam)
=======

#### A ROS Driver for V4L USB Cameras
#### A ROS2 Driver for V4L USB Cameras
This package is based off of V4L devices specifically instead of just UVC.

For full documentation, see [the ROS wiki](http://ros.org/wiki/usb_cam).
For ros1 documentation, see [the ROS wiki](http://ros.org/wiki/usb_cam).

[Doxygen](http://docs.ros.org/indigo/api/usb_cam/html/) files can be found on the ROS wiki.

Expand Down
60 changes: 39 additions & 21 deletions include/usb_cam/usb_cam.h
Original file line number Diff line number Diff line change
Expand Up @@ -52,10 +52,23 @@ extern "C"
#define AV_CODEC_ID_MJPEG CODEC_ID_MJPEG
#endif

#include <builtin_interfaces/msg/time.hpp>
#include <rclcpp/time.hpp>
// #include <sensor_msgs/msg/image.h>
#include <string>
#include <sstream>

#include <sensor_msgs/Image.h>
#define ROS_INFO(msg, ...) printf(msg, ##__VA_ARGS__)
#define ROS_ERROR(msg, ...) printf(msg, ##__VA_ARGS__)
#define ROS_WARN(msg, ...) printf(msg, ##__VA_ARGS__)
#define ROS_DEBUG(msg, ...) printf(msg, ##__VA_ARGS__)
// #define ROS_DEBUG(msg, ...) // ##__VA_ARGS__
#define __FILENAME__ (strrchr(__FILE__, '/') ? strrchr(__FILE__, '/') + 1 : __FILE__)

#define INFO(msg) std::cout << "I [" << __FILENAME__ << ":" << __LINE__ << " " << __FUNCTION__ << "] " << msg << "\n"
#define WARN(msg) std::cout << "W [" << __FILENAME__ << ":" << __LINE__ << " " << __FUNCTION__ << "] " << msg << "\n"
#define ERROR(msg) std::cerr << "E [" << __FILENAME__ << ":" << __LINE__ << " " << __FUNCTION__ << "] " << msg << std::endl
#define ROS_ERROR_STREAM(msg) ERROR(msg)

namespace usb_cam {

Expand All @@ -75,36 +88,40 @@ class UsbCam {
~UsbCam();

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

// grabs a new image from the camera
void grab_image(sensor_msgs::Image* image);
// 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);

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

// Set video device parameters
void set_v4l_parameter(const std::string& param, int value);
void 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);

void stop_capturing(void);
void start_capturing(void);
bool stop_capturing(void);
bool start_capturing(void);
bool is_capturing();

private:
// TODO(lucasw) just store an Image shared_ptr here
typedef struct
{
int width;
int height;
int bytes_per_pixel;
int image_size;
ros::Time stamp;
builtin_interfaces::msg::Time stamp;
char *image;
int is_new;
} camera_image_t;
Expand All @@ -117,20 +134,21 @@ class UsbCam {


int init_mjpeg_decoder(int image_width, int image_height);
void mjpeg2rgb(char *MJPEG, int len, char *RGB, int NumPixels);
void process_image(const void * src, int len, camera_image_t *dest);
int read_frame();
void uninit_device(void);
void init_read(unsigned int buffer_size);
void init_mmap(void);
void init_userp(unsigned int buffer_size);
void init_device(int image_width, int image_height, int framerate);
void close_device(void);
void open_device(void);
void grab_image();
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);
bool init_mmap(void);
bool init_userp(unsigned int buffer_size);
bool init_device(int image_width, int image_height, int framerate);
bool close_device(void);
bool open_device(void);
bool grab_image();
bool is_capturing_;


rclcpp::Clock::SharedPtr clock_;
std::string camera_dev_;
unsigned int pixelformat_;
bool monochrome_;
Expand Down
Loading

0 comments on commit 966ad3d

Please sign in to comment.