提交 ec22443b 编写于 作者: D dengchengliang 提交者: fengqikai1414

update usb_cam driver to cybertron version

上级 9bd16323
load("//tools:cpplint.bzl", "cpplint")
package(default_visibility = ["//visibility:public"])
cc_binary(
name = "libusb_cam_component.so",
deps = [":usb_cam_component_lib"],
linkopts = [
"-shared",
"-lswscale",
"-lavformat",
"-lavcodec",
],
linkstatic = False,
)
cc_library(
name = "usb_cam_component_lib",
srcs = ["usb_cam_component.cc"],
hdrs = ["usb_cam_component.h"],
deps = [
":usb_cam",
"//modules/drivers/proto:sensor_proto",
"//framework:cybertron",
],
copts = ['-DMODULE_NAME=\\"usb_cam\\"']
)
cc_library(
name = "usb_cam",
srcs = [
"usb_cam.cc",
],
hdrs = [
"usb_cam.h",
],
deps = [
"//modules/drivers/usb_cam/proto:usb_cam_proto",
"//framework:cybertron",
"@adv_plat//:adv_plat",
],
)
cpplint()
camera_dev: "/dev/camera/lanemark"
frame_id: "camera_lanemark"
pixel_format: "yuyv"
io_method: IO_METHOD_MMAP
width: 1920
height: 1080
frame_rate: 30
monochrome: false
brightness: -1
contrast: -1
saturation: -1
sharpness: -1
gain: -1
auto_focus: false
focus: -1
auto_exposure: true
exposure: 100
auto_white_balance: true
white_balance: 4000
bytes_per_pixel: 2
trigger_internal: 0
trigger_fps: 20
channel_name: "/apollo/sensor/camera/obstacle/front_6mm"
device_wait: 2.0
spin_rate: 0.005
camera_dev: "/dev/camera/trafficlights"
frame_id: "camera_long"
pixel_format: "yuyv"
io_method: IO_METHOD_MMAP
width: 1920
height: 1080
frame_rate: 30
monochrome: false
brightness: -1
contrast: -1
saturation: -1
sharpness: -1
gain: -1
auto_focus: false
focus: -1
auto_exposure: true
exposure: 100
auto_white_balance: true
white_balance: 4000
bytes_per_pixel: 2
trigger_internal: 0
trigger_fps: 20
channel_name: "/apollo/sensor/camera/traffic/image_long"
device_wait: 2.0
spin_rate: 0.005
camera_dev: "/dev/camera/obstacle"
frame_id: "camera_short"
pixel_format: "yuyv"
io_method: IO_METHOD_MMAP
width: 1920
height: 1080
frame_rate: 30
monochrome: false
brightness: -1
contrast: -1
saturation: -1
sharpness: -1
gain: -1
auto_focus: false
focus: -1
auto_exposure: true
exposure: 100
auto_white_balance: true
white_balance: 4000
bytes_per_pixel: 2
trigger_internal: 0
trigger_fps: 20
channel_name: "/apollo/sensor/camera/traffic/image_short"
device_wait: 2.0
spin_rate: 0.005
# Define all coms in DAG streaming.
module_config {
module_library : "/apollo/bazel-bin/modules/drivers/usb_cam/libusb_cam_component.so"
components {
class_name : "UsbCamComponent"
config {
name : "usb_cam_driver_short"
config_file_path : "/apollo/modules/drivers/usb_cam/conf/usb_cam_short_conf.pb.txt"
readers {channel: ""}
}
}
components {
class_name : "UsbCamComponent"
config {
name : "usb_cam_driver_long"
config_file_path : "/apollo/modules/drivers/usb_cam/conf/usb_cam_long_conf.pb.txt"
readers {channel: ""}
}
}
components {
class_name : "UsbCamComponent"
config {
name : "usb_cam_driver_front"
config_file_path : "/apollo/modules/drivers/usb_cam/conf/usb_cam_front_conf.pb.txt"
readers {channel: ""}
}
}
}
<launch>
<arg name="traffic_short_topic_name" default="/apollo/sensor/camera/traffic/image_short" />
<arg name="traffic_long_topic_name" default="/apollo/sensor/camera/traffic/image_long" />
<arg name="perception_obstacle" default="/apollo/perception/obstacle/camera" />
<arg name="frame_rate" default="30"/>
<arg name="trigger_internal" default="0" />
<arg name="trigger_fps" default="20" />
<group ns="camera_long">
<node pkg="nodelet" type="nodelet" name="camera_nodelet_manager" args="manager" respawn="true" />
<node pkg="nodelet" type="nodelet" name="sensor_camera_traffic_long" output="screen"
args="load usb_cam/UsbCamNodelet camera_nodelet_manager" respawn="true" >
<param name="video_device" value="/dev/camera/trafficlights" />
<param name="image_width" value="1920" />
<param name="image_height" value="1080" />
<param name="pixel_format" value="yuyv" />
<param name="frame_rate" value="$(arg frame_rate)" />
<param name="camera_frame_id" value="usb_cam" />
<param name="io_method" value="mmap"/>
<param name="camera_timeout" value="2000" />
<param name="error_code" value="11" />
<param name="camera_info_url" type="string" value="file://$(find usb_cam)/params/onsemi_traffic_intrinsics.yaml" />
<param name="trigger_internal" value="$(arg trigger_internal)"/>
<param name="trigger_fps" value="$(arg trigger_fps)" />
<remap from="/camera_long/image_raw0" to="$(arg traffic_long_topic_name)" />
<remap from="/apollo/sensor/camera/traffic/camera_info" to="$(arg traffic_long_topic_name)/camera_info" />
</node>
</group>
<group ns="camera_short">
<node pkg="nodelet" type="nodelet" name="camera_nodelet_manager" args="manager" respawn="true" />
<node pkg="nodelet" type="nodelet" name="sensor_camera_traffic_short" output="screen"
args="load usb_cam/UsbCamNodelet camera_nodelet_manager" respawn="true" >
<param name="video_device" value="/dev/camera/obstacle" />
<param name="image_width" value="1920" />
<param name="image_height" value="1080" />
<param name="pixel_format" value="yuyv" />
<param name="frame_rate" value="$(arg frame_rate)" />
<param name="camera_frame_id" value="usb_cam" />
<param name="io_method" value="mmap"/>
<param name="camera_timeout" value="2000" />
<param name="error_code" value="14" />
<param name="camera_info_url" type="string" value="file://$(find usb_cam)/params/onsemi_obstacle_intrinsics.yaml" />
<param name="trigger_internal" value="$(arg trigger_internal)"/>
<param name="trigger_fps" value="$(arg trigger_fps)" />
<remap from="/camera_short/image_raw0" to="$(arg traffic_short_topic_name)" />
<remap from="/apollo/sensor/camera/traffic/camera_info" to="$(arg traffic_short_topic_name)/camera_info" />
</node>
</group>
<group ns="camera_obstacle">
<node pkg="nodelet" type="nodelet" name="camera_nodelet_manager" args="manager" respawn="true" />
<node pkg="nodelet" type="nodelet" name="sensor_camera_obstacle" output="screen"
args="load usb_cam/UsbCamNodelet camera_nodelet_manager" respawn="true" >
<param name="video_device" value="/dev/camera/obstacle" />
<param name="image_width" value="1920" />
<param name="image_height" value="1080" />
<param name="pixel_format" value="yuyv" />
<param name="frame_rate" value="$(arg frame_rate)" />
<param name="camera_frame_id" value="usb_cam" />
<param name="io_method" value="mmap"/>
<param name="camera_timeout" value="2000" />
<param name="error_code" value="14" />
<param name="trigger_internal" value="$(arg trigger_internal)"/>
<param name="trigger_fps" value="$(arg trigger_fps)" />
<param name="camera_info_url" type="string" value="file://$(find usb_cam)/params/onsemi_obstacle_intrinsics.yaml" />
<remap from="/camera_short/image_raw0" to="$(arg perception_obstacle)" />
<remap from="/apollo/sensor/camera/traffic/camera_info" to="$(arg perception_obstacle)/camera_info" />
</node>
</group>
</launch>
<launch>
<arg name="front_obstacle_6mm_topic_name" default="/apollo/sensor/camera/obstacle/front_6mm" />
<arg name="frame_rate" default="30"/>
<group ns="camera_obstacle">
<node pkg="nodelet" type="nodelet" name="camera_nodelet_manager" args="manager" respawn="true" />
<node pkg="nodelet" type="nodelet" name="sensor_camera_obstacle" output="screen"
args="load usb_cam/UsbCamNodelet camera_nodelet_manager" respawn="true" >
<param name="video_device" value="/dev/camera/lanemark" />
<param name="image_width" value="1920" />
<param name="image_height" value="1080" />
<param name="pixel_format" value="yuyv" />
<param name="frame_rate" value="$(arg frame_rate)" />
<param name="camera_frame_id" value="usb_cam" />
<param name="io_method" value="mmap"/>
<param name="camera_timeout" value="2000" />
<param name="error_code" value="14" />
<param name="camera_info_url" type="string" value="file://$(find usb_cam)/params/onsemi_obstacle_intrinsics.yaml" />
<remap from="/camera_obstacle/image_raw0" to="$(arg front_obstacle_6mm_topic_name)" />
<remap from="/apollo/sensor/camera/traffic/camera_info" to="$(arg front_obstacle_6mm_topic_name)/camera_info" />
</node>
</group>
</launch>
<launch>
<arg name="traffic_short_topic_name" default="/apollo/sensor/camera/traffic/image_short" />
<arg name="traffic_long_topic_name" default="/apollo/sensor/camera/traffic/image_long" />
<arg name="frame_rate" default="30"/>
<group ns="camera_long">
<node pkg="nodelet" type="nodelet" name="camera_nodelet_manager" args="manager" respawn="true" />
<node pkg="nodelet" type="nodelet" name="sensor_camera_traffic_long" output="screen"
args="load usb_cam/UsbCamNodelet camera_nodelet_manager" respawn="true" >
<param name="video_device" value="/dev/video0" />
<param name="image_width" value="1920" />
<param name="image_height" value="1080" />
<param name="pixel_format" value="yuyv" />
<param name="frame_rate" value="$(arg frame_rate)" />
<param name="camera_frame_id" value="usb_cam" />
<param name="io_method" value="mmap"/>
<param name="camera_timeout" value="2000" />
<param name="camera_info_url" type="string" value="file://$(find usb_cam)/params/onsemi_traffic_intrinsics.yaml" />
<remap from="/camera_long/image_raw0" to="$(arg traffic_long_topic_name)" />
<remap from="/apollo/sensor/camera/traffic/camera_info" to="$(arg traffic_long_topic_name)/camera_info" />
</node>
</group>
</launch>
<launch>
<node name="usb_cam" pkg="usb_cam" type="usb_cam_node" output="screen" >
<param name="topic_name" value="image_raw0" />
<param name="video_device" value="/dev/video0" />
<param name="image_width" value="1920" />
<param name="image_height" value="1080" />
<param name="pixel_format" value="yuyv" />
<param name="camera_frame_id" value="usb_cam" />
<param name="io_method" value="mmap"/>
</node>
</launch>
<cybertron>
<module>
<name>usb_cam</name>
<dag_conf>/apollo/modules/drivers/usb_cam/dag/dag_streaming_usb_cam.dag</dag_conf>
<process_name>usb_cam</process_name>
</module>
</cybertron>
<library path="lib/libusb_cam_nodelet">
<class name="usb_cam/UsbCamNodelet"
type="usb_cam::UsbCamNodelet"
base_class_type="nodelet::Nodelet">
<description>
usb camera nodelet
</description>
</class>
</library>
/*********************************************************************
*
* Software License Agreement (BSD License)
*
* Copyright (c) 2014, Robert Bosch LLC.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* 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 nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
*********************************************************************/
#include <ros/ros.h>
#include "usb_cam_wrapper.h"
int main(int argc, char **argv)
{
ros::init(argc, argv, "usb_cam");
ros::NodeHandle node;
ros::NodeHandle priv_nh("~");
usb_cam::UsbCamWrapper usbCam(node, priv_nh);
usbCam.spin();
return EXIT_SUCCESS;
}
#include <boost/thread.hpp>
#include <ros/ros.h>
#include <pluginlib/class_list_macros.h>
#include <nodelet/nodelet.h>
#include "usb_cam_wrapper.h"
namespace usb_cam {
class UsbCamNodelet: public nodelet::Nodelet
{
public:
UsbCamNodelet() {}
~UsbCamNodelet() {
ROS_INFO("shutting down driver thread");
if (device_thread_ != nullptr && device_thread_->joinable()) {
device_thread_->join();
}
ROS_INFO("driver thread stopped");
};
private:
virtual void onInit();
boost::shared_ptr<UsbCamWrapper> usb_cam_ = nullptr;
boost::shared_ptr<boost::thread> device_thread_ = nullptr;
};
void UsbCamNodelet::onInit()
{
ROS_INFO("Usb cam nodelet init");
usb_cam_.reset(new UsbCamWrapper(getNodeHandle(), getPrivateNodeHandle()));
// spawn device poll thread
device_thread_ = boost::shared_ptr<boost::thread>
(new boost::thread(boost::bind(&UsbCamWrapper::spin, usb_cam_)));
}
}
// Register this plugin with pluginlib. Names must match nodelets.xml.
//
// parameters: package, class name, class type, base class type
PLUGINLIB_DECLARE_CLASS(usb_cam, UsbCamNodelet,
usb_cam::UsbCamNodelet, nodelet::Nodelet);
#include "usb_cam_wrapper.h"
#include <time.h> /* for clock_gettime */
#include "image_transport/camera_common.h"
#include "image_transport/publisher_plugin.h"
namespace usb_cam {
UsbCamWrapper::UsbCamWrapper(ros::NodeHandle node, ros::NodeHandle private_nh) :
node_(node), priv_node_(private_nh), last_stamp_(0)
{
// grab the parameters
priv_node_.param("topic_name", topic_name_, std::string("image_raw0"));
priv_node_.param("video_device", video_device_name_, std::string("/dev/video0"));
priv_node_.param("brightness", brightness_, -1); //0-255, -1 "leave alone"
priv_node_.param("contrast", contrast_, -1); //0-255, -1 "leave alone"
priv_node_.param("saturation", saturation_, -1); //0-255, -1 "leave alone"
priv_node_.param("sharpness", sharpness_, -1); //0-255, -1 "leave alone"
// possible values: mmap, read, userptr
priv_node_.param("io_method", io_method_name_, std::string("mmap"));
priv_node_.param("image_width", image_width_, 640);
priv_node_.param("image_height", image_height_, 480);
priv_node_.param("frame_rate", framerate_, 30);
priv_node_.param("trigger_internal", trigger_internal_, 0); //default gps pps
priv_node_.param("trigger_fps", trigger_fps_, 30);
// possible values: yuyv, uyvy, mjpeg, yuvmono10, rgb24
priv_node_.param("pixel_format", pixel_format_name_, std::string("mjpeg"));
// enable/disable autofocus
priv_node_.param("autofocus", autofocus_, false);
priv_node_.param("focus", focus_, -1); //0-255, -1 "leave alone"
// enable/disable autoexposure
priv_node_.param("autoexposure", autoexposure_, true);
priv_node_.param("exposure", exposure_, 100);
priv_node_.param("gain", gain_, -1); //0-100?, -1 "leave alone"
// enable/disable auto white balance temperature
priv_node_.param("auto_white_balance", auto_white_balance_, true);
priv_node_.param("white_balance", white_balance_, 4000);
// load the camera info
priv_node_.param("camera_frame_id", img_.header.frame_id, std::string("head_camera"));
priv_node_.param("camera_name", camera_name_, std::string("head_camera"));
priv_node_.param("camera_info_url", camera_info_url_, std::string(""));
cinfo_.reset(new camera_info_manager::CameraInfoManager(node_, camera_name_, camera_info_url_));
// default 3000 ms
priv_node_.param("camera_timeout", cam_timeout_, 1000);
priv_node_.param("spin_interval", spin_interval_, 0.005f);
// Warning when diff with last > 1.5* interval
frame_warning_interval_ = 1.5 / framerate_;
// now max fps 30, we use a appox time 0.9 to drop image.
frame_drop_interval_ = 0.9 / framerate_;
// advertise the main image topic
//image_transport::ImageTransport it(node_);
//image_pub_ = it.advertiseCamera(topic_name_, 1);
// Load transport publish plugin
std::string image_topic = node_.resolveName(topic_name_);
pub_loader_ = boost::make_shared<image_transport::PubLoader>("image_transport", "image_transport::PublisherPlugin");
std::string lookup_name = image_transport::PublisherPlugin::getLookupName(std::string("raw"));
image_pub_plugin_ = pub_loader_->createInstance(lookup_name);
if (image_pub_plugin_ != nullptr)
{
image_pub_plugin_->advertise(node_, image_topic, 1, image_transport::SubscriberStatusCallback(),
image_transport::SubscriberStatusCallback(), ros::VoidPtr(), false);
}
else
{
ROS_ERROR("create image publish plugin error. lookup_name: '%s'", lookup_name.c_str());
node_.shutdown();
return;
}
// camera info publish
std::string cam_info_topic = image_transport::getCameraInfoTopic(image_topic);
cam_info_pub_ = node_.advertise<sensor_msgs::CameraInfo>(cam_info_topic, 1, ros::SubscriberStatusCallback(),
ros::SubscriberStatusCallback(), ros::VoidPtr(), false);
// create Services
service_start_ = node_.advertiseService("start_capture", &UsbCamWrapper::service_start_cap, this);
service_stop_ = node_.advertiseService("stop_capture", &UsbCamWrapper::service_stop_cap, this);
// check for default camera info
if (!cinfo_->isCalibrated())
{
cinfo_->setCameraName(video_device_name_);
sensor_msgs::CameraInfo camera_info;
camera_info.header.frame_id = img_.header.frame_id;
camera_info.width = image_width_;
camera_info.height = image_height_;
cinfo_->setCameraInfo(camera_info);
}
//get the camera basical infomation
cam_info_.reset(new sensor_msgs::CameraInfo(cinfo_->getCameraInfo()));
ROS_INFO("Starting '%s' (%s) at %dx%d via %s (%s) at %i FPS", camera_name_.c_str(),
video_device_name_.c_str(),
image_width_, image_height_, io_method_name_.c_str(), pixel_format_name_.c_str(), framerate_);
// set the IO method
UsbCam::io_method io_method = UsbCam::io_method_from_string(io_method_name_);
if (io_method == UsbCam::IO_METHOD_UNKNOWN)
{
ROS_FATAL("Unknown IO method '%s'", io_method_name_.c_str());
node_.shutdown();
return;
}
// set the pixel format
UsbCam::pixel_format pixel_format = UsbCam::pixel_format_from_string(pixel_format_name_);
if (pixel_format == UsbCam::PIXEL_FORMAT_UNKNOWN)
{
ROS_FATAL("Unknown pixel format '%s'", pixel_format_name_.c_str());
node_.shutdown();
return;
}
// start the camera
cam_.start(video_device_name_.c_str(), io_method, pixel_format, image_width_, image_height_,
framerate_);
// set camera parameters
if (brightness_ >= 0)
cam_.set_v4l_parameter("brightness", brightness_);
if (contrast_ >= 0)
cam_.set_v4l_parameter("contrast", contrast_);
if (saturation_ >= 0)
cam_.set_v4l_parameter("saturation", saturation_);
if (sharpness_ >= 0)
cam_.set_v4l_parameter("sharpness", sharpness_);
if (gain_ >= 0)
cam_.set_v4l_parameter("gain", gain_);
// check auto white balance
if (auto_white_balance_)
{
cam_.set_v4l_parameter("white_balance_temperature_auto", 1);
}
else
{
cam_.set_v4l_parameter("white_balance_temperature_auto", 0);
cam_.set_v4l_parameter("white_balance_temperature", white_balance_);
}
// check auto exposure
if (!autoexposure_)
{
// turn down exposure control (from max of 3)
cam_.set_v4l_parameter("exposure_auto", 1);
// change the exposure level
cam_.set_v4l_parameter("exposure_absolute", exposure_);
}
// check auto focus
if (autofocus_)
{
cam_.set_auto_focus(1);
cam_.set_v4l_parameter("focus_auto", 1);
}
else
{
cam_.set_v4l_parameter("focus_auto", 0);
if (focus_ >= 0)
cam_.set_v4l_parameter("focus_absolute", focus_);
}
//trigger enable
int trigger_ret = cam_.trigger_enable(trigger_fps_, trigger_internal_);
if (0 != trigger_ret)
{
ROS_WARN("Camera trigger Fail ret '%d'", trigger_ret);
// node_.shutdown();
// return;
}
}
UsbCamWrapper::~UsbCamWrapper()
{
cam_.shutdown();
}
bool UsbCamWrapper::service_start_cap(std_srvs::Empty::Request& req,
std_srvs::Empty::Response& res)
{
cam_.start_capturing();
return true;
}
bool UsbCamWrapper::service_stop_cap(std_srvs::Empty::Request& req,
std_srvs::Empty::Response& res)
{
cam_.stop_capturing();
return true;
}
bool UsbCamWrapper::take_and_send_image()
{
// grab the image
bool get_new_image = cam_.grab_image(&img_, cam_timeout_);
if (!get_new_image)
return false;
// grab the camera info
//cam_info_ = sensor_msgs::CameraInfo(cinfo_->getCameraInfo());
cam_info_->header.frame_id = img_.header.frame_id;
cam_info_->header.stamp = img_.header.stamp;
if (last_stamp_ == ros::Time(0))
{
last_stamp_ = img_.header.stamp;
}
else
{
auto diff = (img_.header.stamp - last_stamp_).toSec();
// drop image by frame_rate
if (diff < frame_drop_interval_) {
ROS_INFO_STREAM("drop image:" << img_.header.stamp);
return true;
}
if (frame_warning_interval_ < diff)
ROS_WARN_STREAM("stamp jump.last stamp:" << last_stamp_
<< " current stamp:" << img_.header.stamp);
last_stamp_ = img_.header.stamp;
}
// publish the image
image_pub_plugin_->publish(img_);
cam_info_pub_.publish(cam_info_);
return true;
}
bool UsbCamWrapper::spin()
{
// spin loop rate should be in accord with the trigger frequence
ros::Duration loop_interval(this->spin_interval_);
while (node_.ok())
{
if (cam_.is_capturing())
if (!take_and_send_image())
ROS_ERROR("USB camera did not respond in time.");
//ros::spinOnce();
loop_interval.sleep();
}
return true;
}
}
#ifndef USB_CAM_INCLUDE_USB_CAM_USBCAMWRAPPER_H_
#define USB_CAM_INCLUDE_USB_CAM_USBCAMWRAPPER_H_
#include <ros/ros.h>
#include <usb_cam/usb_cam.h>
#include <image_transport/image_transport.h>
#include <camera_info_manager/camera_info_manager.h>
#include <pluginlib/class_loader.h>
#include <sstream>
#include <std_srvs/Empty.h>
namespace usb_cam {
enum TriggerFrequence {
FPS_10HZ = 10,
FPS_15HZ = 15,
FPS_20HZ = 20,
DEFAULT_FPS = 30
};
class UsbCamWrapper {
public:
UsbCamWrapper(ros::NodeHandle node, ros::NodeHandle private_nh);
virtual ~UsbCamWrapper();
bool service_start_cap(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res);
bool service_stop_cap(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res);
bool take_and_send_image();
bool spin();
private:
// shared image message
sensor_msgs::Image img_;
sensor_msgs::CameraInfoPtr cam_info_ = nullptr;
//image_transport::CameraPublisher image_pub_;
image_transport::PubLoaderPtr pub_loader_;
boost::shared_ptr<image_transport::PublisherPlugin> image_pub_plugin_;
ros::Publisher cam_info_pub_;
// parameters
std::string topic_name_;
std::string video_device_name_;
std::string io_method_name_;
std::string pixel_format_name_;
std::string camera_name_;
std::string camera_info_url_;
//std::string start_service_name_, start_service_name_;
//bool streaming_status_;
int image_width_;
int image_height_;
int framerate_;
int exposure_;
int brightness_;
int contrast_;
int saturation_;
int sharpness_;
int focus_;
int white_balance_;
int gain_;
int trigger_internal_;
int trigger_fps_;
bool autofocus_;
bool autoexposure_;
bool auto_white_balance_;
// usb will be reset when camera timeout
int cam_timeout_;
UsbCam cam_;
boost::shared_ptr<camera_info_manager::CameraInfoManager> cinfo_;
ros::ServiceServer service_start_;
ros::ServiceServer service_stop_;
// private ROS node handle
ros::NodeHandle node_;
ros::NodeHandle priv_node_;
ros::Time last_stamp_;
float frame_warning_interval_;
float frame_drop_interval_;
float spin_interval_;
int error_code_;
};
}
#endif /* USB_CAM_INCLUDE_USB_CAM_USBCAMWRAPPER_H_ */
<package>
<name>usb_cam</name>
<version>0.3.4</version>
<description>A ROS Driver for V4L USB Cameras</description>
<maintainer email="rctoris@wpi.edu">Russell Toris</maintainer>
<author email="benjamin.pitzer@bosch.com">Benjamin Pitzer</author>
<license>BSD</license>
<url type="website">http://wiki.ros.org/usb_cam</url>
<url type="bugtracker">https://github.com/bosch-ros-pkg/usb_cam/issues</url>
<url type="repository">https://github.com/bosch-ros-pkg/usb_cam</url>
<buildtool_depend>catkin</buildtool_depend>
<build_depend>image_transport</build_depend>
<build_depend>roscpp</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>std_srvs</build_depend>
<build_depend>sensor_msgs</build_depend>
<build_depend>ffmpeg</build_depend>
<build_depend>camera_info_manager</build_depend>
<build_depend>nodelet</build_depend>
<build_depend>pluginlib</build_depend>
<run_depend>image_transport</run_depend>
<run_depend>roscpp</run_depend>
<run_depend>std_msgs</run_depend>
<run_depend>std_srvs</run_depend>
<run_depend>sensor_msgs</run_depend>
<run_depend>ffmpeg</run_depend>
<run_depend>camera_info_manager</run_depend>
<run_depend>v4l-utils</run_depend>
<run_depend>nodelet</run_depend>
<run_depend>pluginlib</run_depend>
<export>
<nodelet plugin="${prefix}/nodelets.xml"/>
</export>
</package>
image_width: 1080
image_height: 1920
camera_name: usb_cam
camera_matrix:
rows: 3
cols: 3
data: [4827.94, 0, 1223.5, 0, 4835.62, 1024.5, 0, 0, 1]
distortion_model: plumb_bob
distortion_coefficients:
rows: 1
cols: 5
data: [-0.41527, 0.31874, -0.00197, 0.00071, 0]
rectification_matrix:
rows: 3
cols: 3
data: [1, 0, 0, 0, 1, 0, 0, 0, 1]
projection_matrix:
rows: 3
cols: 4
data: [4827.94, 0, 1223.5, 0, 0, 4835.62, 1024.5, 0, 0, 0, 1, 0]
image_width: 1080
image_height: 1920
camera_name: usb_cam
camera_matrix:
rows: 3
cols: 3
data: [4827.94, 0, 1223.5, 0, 4835.62, 1024.5, 0, 0, 1]
distortion_model: plumb_bob
distortion_coefficients:
rows: 1
cols: 5
data: [-0.41527, 0.31874, -0.00197, 0.00071, 0]
rectification_matrix:
rows: 3
cols: 3
data: [1, 0, 0, 0, 1, 0, 0, 0, 1]
projection_matrix:
rows: 3
cols: 4
data: [4827.94, 0, 1223.5, 0, 0, 4835.62, 1024.5, 0, 0, 0, 1, 0]
load("//tools:cpplint.bzl", "cpplint")
package(default_visibility = ["//visibility:public"])
cc_library(
name = "usb_cam_proto",
deps = [
":sensor_usb_cam_proto",
],
)
cc_proto_library(
name = "sensor_usb_cam_proto",
deps = [
":usb_cam_proto_lib",
],
)
proto_library(
name = "usb_cam_proto_lib",
srcs = [
"config.proto",
],
deps = [
"//modules/common/proto:header_proto_lib",
],
)
cpplint()
syntax = "proto2";
package apollo.drivers.usb_cam.config;
enum IOMethod {
IO_METHOD_UNKNOWN = 0;
IO_METHOD_READ = 1;
IO_METHOD_MMAP = 2;
IO_METHOD_USERPTR = 3;
}
message Config {
required string camera_dev = 1;
required string frame_id = 2;
//v4l pixel format
required string pixel_format = 3 [default="yuyv"];
//mmap, userptr, read
required IOMethod io_method = 4;
required uint32 width = 5;
required uint32 height = 6;
required uint32 frame_rate = 7;
required bool monochrome = 8 [default=false];
required int32 brightness = 9 [default=-1];
required int32 contrast = 10 [default=-1];
required int32 saturation = 11 [default=-1];
required int32 sharpness = 12 [default=-1];
required int32 gain = 13 [default=-1];
required bool auto_focus = 14 [default=false];
required int32 focus = 15 [default=-1];
required bool auto_exposure = 16 [default=true];
required int32 exposure = 17 [default=100];
required bool auto_white_balance = 18 [default=true];
required int32 white_balance = 19 [default=4000];
required uint32 bytes_per_pixel = 20 [default=3];
required uint32 trigger_internal = 21 [default=0];
required uint32 trigger_fps = 22 [default=30];
optional string channel_name = 23 [ default="" ];
// wait time when camera select timeout
optional float device_wait = 24 [ default=2.0];
// camera select spin time
optional float spin_rate = 25 [ default=0.005];
}
Video for Linux Two API Specification
Revision 0.24
Michael H Schimek <mschimek@gmx.at>
Bill Dirks
Hans Verkuil
Martin Rubli
Copyright © 1999, 2000, 2001, 2002, 2003, 2004, 2005, 2006, 2007, 2008 Bill Dirks, Michael H. Schimek, Hans Verkuil, Martin Rubli
This document is copyrighted © 1999-2008 by Bill Dirks, Michael H. Schimek, Hans Verkuil and Martin Rubli.
Permission is granted to copy, distribute and/or modify this document under the terms of the GNU Free Documentation License, Version 1.1 or any later version published by the Free Software Foundation; with no Invariant Sections, with no Front-Cover Texts, and with no Back-Cover Texts. A copy of the license is included in the appendix entitled "GNU Free Documentation License".
Programming examples can be used and distributed without restrictions.
此差异已折叠。
此差异已折叠。
......@@ -33,130 +33,140 @@
* POSSIBILITY OF SUCH DAMAGE.
*
*********************************************************************/
#ifndef USB_CAM_USB_CAM_H
#define USB_CAM_USB_CAM_H
#ifndef MODULES_DRIVERS_USB_CAM_USB_CAM_H_
#define MODULES_DRIVERS_USB_CAM_USB_CAM_H_
#include <asm/types.h> /* for videodev2.h */
#include <memory>
#include <sys/ioctl.h>
#include <sys/mman.h>
#include <malloc.h>
#include <immintrin.h>
#include <x86intrin.h>
extern "C" {
#include <linux/videodev2.h>
#include <libavcodec/avcodec.h>
#include <libavutil/mem.h>
#include <libswscale/swscale.h>
#include <linux/usb/video.h>
#include <linux/uvcvideo.h>
#include <linux/videodev2.h>
#include <libavutil/mem.h>
}
// legacy reasons
#include <libavcodec/version.h>
#if LIBAVCODEC_VERSION_MAJOR < 55
#define AV_CODEC_ID_MJPEG CODEC_ID_MJPEG
#endif
#include <sstream>
#include <string>
#include <sstream>
#include <sensor_msgs/Image.h>
namespace usb_cam {
class UsbCam {
public:
typedef enum {
IO_METHOD_MMAP,
IO_METHOD_UNKNOWN,
} io_method;
typedef enum {
PIXEL_FORMAT_YUYV,
PIXEL_FORMAT_UYVY,
PIXEL_FORMAT_MJPEG,
PIXEL_FORMAT_YUVMONO10,
PIXEL_FORMAT_RGB24,
PIXEL_FORMAT_UNKNOWN
} pixel_format;
#include "cybertron/cybertron.h"
UsbCam();
~UsbCam();
#include "modules/drivers/usb_cam/proto/config.pb.h"
// start camera
void start(const std::string &dev, io_method io, pixel_format pf,
int image_width, int image_height, int framerate);
// shutdown camera
void shutdown(void);
namespace apollo {
namespace drivers {
namespace usb_cam {
// grabs a new image from the camera
bool grab_image(sensor_msgs::Image *image, int timeout);
using apollo::drivers::usb_cam::config::Config;
using apollo::drivers::usb_cam::config::IO_METHOD_READ;
using apollo::drivers::usb_cam::config::IO_METHOD_MMAP;
using apollo::drivers::usb_cam::config::IO_METHOD_USERPTR;
using apollo::drivers::usb_cam::config::IO_METHOD_UNKNOWN;
// camera raw image struct
struct CameraImage {
int width;
int height;
int bytes_per_pixel;
int image_size;
int is_new;
int tv_sec;
int tv_usec;
char* image;
~CameraImage() {
if (image != nullptr) {
free((void*)image);
image = nullptr;
}
}
};
// enables/disable auto focus
void set_auto_focus(int value);
typedef std::shared_ptr<CameraImage> CameraImagePtr;
// 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);
struct buffer {
void* start;
size_t length;
};
// enable video triggers //see libadv_trigger_ctl
int trigger_enable(unsigned char fps, unsigned char internal);
int trigger_disable();
class UsbCam {
public:
UsbCam();
virtual ~UsbCam();
static io_method io_method_from_string(const std::string &str);
static pixel_format pixel_format_from_string(const std::string &str);
virtual bool init(
std::shared_ptr<Config>& camera_config);
// user use this function to get camera frame data
virtual bool poll(const CameraImagePtr& raw_image);
void stop_capturing(void);
void start_capturing(void);
bool is_capturing();
bool wait_for_device(void);
private:
struct CameraImage {
int width;
int height;
int bytes_per_pixel;
int image_size;
char *image;
int is_new;
int tv_sec;
int tv_usec;
};
struct Buffer {
void *start;
size_t length;
};
int xioctl(int fd, int request, void * arg);
bool init_device(void);
bool uninit_device(void);
int init_mjpeg_decoder(int image_width, int image_height);
void mjpeg2rgb(char *MJPEG, int len, char *RGB, int NumPixels);
bool process_image(const void *src, int len,
boost::shared_ptr<CameraImage> 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);
// TODO
// void reset_device(void);
bool grab_image(int timeout);
void set_device_config();
// enables/disable auto focus
void 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 is_capturing_;
std::string camera_dev_;
unsigned int pixelformat_;
bool monochrome_;
io_method io_;
int init_mjpeg_decoder(int image_width, int image_height);
void mjpeg2rgb(char* mjepg_buffer, int len, char* rgb_buffer, int pixels);
bool init_read(unsigned int buffer_size);
bool init_mmap(void);
bool init_userp(unsigned int buffer_size);
bool set_adv_trigger(void);
bool close_device(void);
bool open_device(void);
bool read_frame(CameraImagePtr raw_image);
bool process_image(const void* src, int len, CameraImagePtr dest);
bool start_capturing(void);
bool stop_capturing(void);
void reconnect();
void reset_device();
std::shared_ptr<Config> config_;
int pixel_format_;
int fd_;
std::vector<Buffer> buffers_;
buffer* buffers_;
unsigned int n_buffers_;
AVFrame *avframe_camera_;
AVFrame *avframe_rgb_;
AVCodec *avcodec_;
AVDictionary *avoptions_;
AVCodecContext *avcodec_context_;
bool is_capturing_;
long image_seq_;
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_;
boost::shared_ptr<CameraImage> image_;
struct SwsContext* video_sws_;
float frame_warning_interval_;
float device_wait_sec_;
uint64_t last_nsec_;
float frame_drop_interval_;
};
}
}
}
#endif
#endif // ONBOARD_DRIVERS_USB_CAMERA_INCLUDE_USB_CAMERA_CAMERA_DEVICE_H
/******************************************************************************
* Copyright 2017 The Apollo Authors. All Rights Reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/
#include "modules/drivers/usb_cam/usb_cam_component.h"
namespace apollo {
namespace drivers {
namespace usb_cam {
bool UsbCamComponent::Init() {
camera_config_ = std::make_shared<Config>();
if(!apollo::cybertron::common::GetProtoFromFile(config_file_path_, camera_config_.get())){
return false;
}
AINFO << "UsbCam config: " << camera_config_->DebugString();
camera_device_.reset(new UsbCam());
camera_device_->init(camera_config_);
raw_image_.reset(new CameraImage);
raw_image_->width = camera_config_->width();
raw_image_->height = camera_config_->height();
raw_image_->bytes_per_pixel = camera_config_->bytes_per_pixel();
device_wait_ = camera_config_->device_wait();
spin_rate_ = camera_config_->spin_rate();
raw_image_->image_size =
raw_image_->width * raw_image_->height * raw_image_->bytes_per_pixel;
raw_image_->is_new = 0;
// free memory in this struct desturctor
raw_image_->image = (char*)calloc(raw_image_->image_size, sizeof(char));
pb_image_.reset(new Image);
pb_image_->mutable_header()->set_frame_id(camera_config_->frame_id());
pb_image_->set_encoding("yuyv");
pb_image_->set_width(raw_image_->width);
pb_image_->set_height(raw_image_->height);
pb_image_->set_step(2 * raw_image_->width);
pb_image_->mutable_data()->reserve(raw_image_->image_size);
writer_ = node_->CreateWriter<Image>(camera_config_->channel_name());
device_thread_ = std::shared_ptr<std::thread>(
new std::thread(std::bind(&UsbCamComponent::run, this)));
device_thread_->detach();
return true;
}
void UsbCamComponent::run() {
while (!cybertron::IsShutdown()) {
if (!camera_device_->wait_for_device()) {
//sleep 2s for next check
sleep(device_wait_);
continue;
}
if (!camera_device_->poll(raw_image_)) {
LOG_ERROR << "camera device poll failed";
continue;
}
cybertron::Time image_time(raw_image_->tv_sec, 1000 * raw_image_->tv_usec);
pb_image_->mutable_header()->set_timestamp_sec(cybertron::Time::Now().ToSecond());
pb_image_->set_measurement_time(image_time.ToSecond());
pb_image_->set_data(raw_image_->image, raw_image_->image_size);
writer_->Write(pb_image_);
sleep(spin_rate_);
}
}
}
}
} // namespace cybertron
/******************************************************************************
* Copyright 2017 The Apollo Authors. All Rights Reserved.
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*****************************************************************************/
#ifndef MODULES_DRIVERS_USB_CAM_USB_CAM_COMPONENT_H
#define MODULES_DRIVERS_USB_CAM_USB_CAM_COMPONENT_H
#include <memory>
#include "cybertron/cybertron.h"
#include "modules/drivers/usb_cam/proto/config.pb.h"
#include "modules/drivers/proto/sensor_image.pb.h"
#include "modules/drivers/usb_cam/usb_cam.h"
namespace apollo {
namespace drivers {
namespace usb_cam {
using apollo::drivers::usb_cam::config::Config;
using apollo::drivers::Image;
using apollo::cybertron::Component;
using apollo::cybertron::Writer;
using apollo::cybertron::Reader;
class UsbCamComponent : public Component<> {
public:
bool Init() override;
private:
void run();
std::shared_ptr<Writer<Image>> writer_ = nullptr;
std::unique_ptr<UsbCam> camera_device_;
std::shared_ptr<Config> camera_config_;
CameraImagePtr raw_image_ = nullptr;
std::shared_ptr<Image> pb_image_ = nullptr;
std::shared_ptr<std::thread> device_thread_;
float spin_rate_ = 0.005;
float device_wait_ = 2.0;
};
CYBERTRON_REGISTER_COMPONENT(UsbCamComponent)
}
}
} // namespace cybertron
#endif // ONBOARD_DRIVERS_USB_CAMERA_INCLUDE_USB_CAMERA_COMPONENT_H
......@@ -5,8 +5,8 @@ licenses(["notice"])
cc_library(
name = "adv_plat",
srcs = [
"lib/libadv_bcan.a",
"lib/libadv_trigger.a",
"lib/libadv_bcan.so.1",
"lib/libadv_trigger.so.1",
],
hdrs = [
"include/adv_trigger.h",
......@@ -18,3 +18,4 @@ cc_library(
linkopts = [
],
)
Markdown is supported
0% .
You are about to add 0 people to the discussion. Proceed with caution.
先完成此消息的编辑!
想要评论请 注册