Go to the documentation of this file.
34 #include <opencv2/video/video.hpp>
40 pnh_.
param<std::string>(
"video_url",
video_url_,
"rtsp://admin:A123456789@192.168.1.64/live.sdp?:network-cache=300");
56 ROS_WARN_STREAM(
"Could not load camera info, using an uncalibrated config.");
89 out_msg.
image = frame;
91 sensor_msgs::CameraInfo camera_info;
96 sensor_msgs::Image rosimg;
125 int main(
int argc,
char **argv)
sensor_msgs::CameraInfo getCameraInfo(void)
image_transport::ImageTransport image_transport_
#define ROS_ERROR_STREAM(args)
uint32_t getNumSubscribers() const
sensor_msgs::ImagePtr toImageMsg() const
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
bool getParam(const std::string &key, bool &b) const
image_transport::CameraPublisher camera_pub_
std::string camera_info_url_
ROSCPP_DECL void spinOnce()
bool loadCameraInfo(const std::string &url)
ServiceServer advertiseService(AdvertiseServiceOptions &ops)
void publish(const sensor_msgs::Image &image, const sensor_msgs::CameraInfo &info) const
CameraPublisher advertiseCamera(const std::string &base_topic, uint32_t queue_size, bool latch=false)
#define ROS_WARN_STREAM(args)
camera_info_manager::CameraInfoManager camera_info_manager_
#define ROS_INFO_ONCE(...)
#define ROS_INFO_STREAM(args)
ros::ServiceServer refresh_service_server_
int main(int argc, char **argv)
bool validateURL(const std::string &url)
#define ROS_WARN_STREAM_DELAYED_THROTTLE(period, args)
bool refreshSrvCallback(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
bool setCameraName(const std::string &cname)
T param(const std::string ¶m_name, const T &default_val) const
ipcamera_driver
Author(s): Alireza Hosseini
autogenerated on Wed Mar 2 2022 00:26:09