Go to the documentation of this file.
37 #include <linux/videodev2.h>
81 std::stringstream output_stream;
82 std::cout <<
"SUPPORTED INPUT FORMATS FOR V4L DEVICE " <<
video_device_name << std::endl;
85 output_stream <<
" | " << fmt.format.description
86 <<
" [" << fmt.interval.width <<
" x "
87 << fmt.interval.height <<
"], "
88 << fmt.interval.discrete.denominator / fmt.interval.discrete.numerator
90 std::cout <<
"\t" << fmt.format.description
91 <<
" [" << fmt.interval.width <<
" x "
92 << fmt.interval.height <<
"], "
93 << fmt.interval.discrete.denominator / fmt.interval.discrete.numerator
94 <<
" fps" << std::endl;
97 response.message = output_stream.str();
103 std::stringstream output_stream;
104 std::cout <<
"SUPPORTED V4L CONTROLS FOR DEVICE " <<
video_device_name << std::endl;
105 std::cout <<
"NOTE: these controls are supported on host machine, not natively by ROS!" << std::endl;
108 output_stream <<
" | " << c.name <<
" [" << c.value <<
"]: " << c.description;
109 std::cout << c.name <<
" [" << c.value <<
"]" << std::endl <<
"\t" << c.description << std::endl;
112 response.message = output_stream.str();
120 _image_transport(node)
143 ROS_INFO(
"Initializing ROS V4L USB camera '%s' (%s) at %dx%d via %s (%s) at %i FPS",
158 sensor_msgs::CameraInfo camera_info_msg;
159 camera_info_msg.header.frame_id =
img_msg->header.frame_id;
167 ROS_ERROR(
"Initialization error or wrong parameters");
179 ROS_INFO(
"Advertising std_srvs::Trigger supported formats information service under name 'supported_formats'");
182 ROS_INFO(
"Advertising std_srvs::Trigger supported V4L controls information service under name 'supported_controls'");
196 ROS_WARN(
"NOTE: the parameters generated for V4L intrinsic camera controls will be placed under namespace 'intrinsic_controls'");
197 ROS_INFO(
"Use 'intrinsic_controls/ignore' list to enumerate the controls provoking errors or the ones you just want to keep untouched");
200 ROS_INFO(
"Attempting to generate ROS parameter for V4L2 control '%s':\n\t%s [%s]%s", c->name.c_str(), c->description.c_str(), c->value.c_str(), c->type == V4L2_CTRL_TYPE_BOOLEAN ?
" (bool 1/0)" :
"");
204 bool generated =
true;
208 case V4L2_CTRL_TYPE_INTEGER:
209 case V4L2_CTRL_TYPE_MENU:
210 case V4L2_CTRL_TYPE_INTEGER_MENU:
212 node.
param<
int>(
"intrinsic_controls/" + c->name, tpi, std::stoi(c->value));
213 c->value = std::to_string(tpi);
215 case V4L2_CTRL_TYPE_BOOLEAN:
217 node.
param<
bool>(
"intrinsic_controls/" + c->name, tpb, c->value ==
"1" ? true :
false);
218 c->value = tpb ? std::to_string(1) : std::to_string(0);
220 case V4L2_CTRL_TYPE_STRING:
222 node.
param<std::string>(
"intrinsic_controls/" + c->name, tps, c->value);
225 case V4L2_CTRL_TYPE_INTEGER64:
226 node.
param<std::string>(
"intrinsic_controls/" + c->name, tps, c->value);
229 tpl = std::stol(tps);
230 ROS_INFO(
"64-bit integer 0x%lX successfully transposed to control %s", tpl, c->name.c_str());
233 catch(std::invalid_argument)
235 ROS_ERROR(
"Cannot convert string value '%s' to 64-bit integer! Please check your configuration file! Dropping down parameter '%s'", tps.c_str(), std::string(
"intrinsic_controls/" + c->name).c_str());
240 ROS_WARN(
"Unsupported type descriptor (%u) for V4L control '%s'. This parameter cannot be set via ROS. Please consider to set this parameter via 3rd party controller application", c->type, c->name.c_str());
244 ROS_INFO(
"Parameter intrinsic_controls/%s exposed with value %s", c->name.c_str(), c->value.c_str());
246 std::vector<std::string>ignored;
247 node.
param< std::vector<std::string> >(
"intrinsic_controls/ignore", ignored, std::vector<std::string>());
275 ROS_ERROR(
"Error starting capture device");
286 if(new_image ==
nullptr)
288 ROS_ERROR(
"Video4linux: frame grabber failed");
293 if (
img_msg->data.size() !=
static_cast<size_t>(new_image->
step * new_image->
height))
const std::string response
static bool service_stop_callback(std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
static bool create_suspended
ros::ServiceServer _service_supported_controls
static std::vector< capture_format_t > supported_formats
static std::string camera_info_url
virtual sensor_msgs::CameraInfo getCameraInfo(void)
static bool full_ffmpeg_log
static bool service_supported_formats_callback(std_srvs::Trigger::Request &request, std_srvs::Trigger::Response &response)
static void v4l_query_controls()
bool getParam(const std::string &key, bool &b) const
static ros::Timer * frame_timer
bool deleteParam(const std::string &key) const
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
void publish(const sensor_msgs::Image &image, const sensor_msgs::CameraInfo &info) const
static bool streaming_status
static std::string camera_frame_id
static std::string io_method_name
static ros::ServiceServer * service_start
ros::ServiceServer _service_stop
static std::vector< camera_control_t > controls
std::string _service_start_name
static sensor_msgs::Image * img_msg
static std::string color_format_name
std::string _service_stop_name
static ros::ServiceServer * service_supported_formats
static UsbCam & Instance()
virtual bool isCalibrated(void)
static bool service_supported_controls_callback(std_srvs::Trigger::Request &request, std_srvs::Trigger::Response &response)
static std::vector< capture_format_t > & get_supported_formats()
static image_transport::ImageTransport * image_transport
virtual bool setCameraInfo(const sensor_msgs::CameraInfo &camera_info)
image_transport::ImageTransport _image_transport
static void adjust_camera()
static std::string video_device_name
sensor_msgs::Image _img_msg
virtual bool setCameraName(const std::string &cname)
static bool start_capture()
static ros::ServiceServer * service_supported_controls
static image_transport::CameraPublisher * image_pub
T param(const std::string ¶m_name, const T &default_val) const
static std::set< std::string > ignore_controls
image_transport::CameraPublisher _image_pub
static std::string camera_name
static std::string camera_transport_suffix
static bool service_start_callback(std_srvs::Empty::Request &request, std_srvs::Empty::Response &response)
static std::string pixel_format_name
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
static camera_info_manager::CameraInfoManager * camera_info
static ros::ServiceServer * service_stop
ros::ServiceServer _service_start
ros::ServiceServer _service_supported_formats
static camera_image_t * read_frame()
static void frame_timer_callback(const ros::TimerEvent &event)
usb_cam
Author(s): Benjamin Pitzer
autogenerated on Sun Sep 3 2023 02:44:54