Skip to content

Commit

Permalink
rename: Rename package name to ipcamera_driver
Browse files Browse the repository at this point in the history
  • Loading branch information
alireza-hosseini committed Aug 6, 2018
1 parent 37f6e6c commit e85ad06
Show file tree
Hide file tree
Showing 6 changed files with 15 additions and 15 deletions.
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
cmake_minimum_required(VERSION 2.8.3)
project(mrl_ipcamera)
project(ipcamera_driver)


find_package(catkin REQUIRED COMPONENTS
Expand Down
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
# mrl_ipcamera
# ipcamera_driver
Simple node to publish regular IP camera video streams to a ros topic.

## Nodes
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -29,8 +29,8 @@

/* Author: Alireza Hosseini */

#ifndef MRL_IPCAMERA
#define MRL_IPCAMERA
#ifndef IPCAMERA_DRIVER_HPP
#define IPCAMERA_DRIVER_HPP

#include <camera_info_manager/camera_info_manager.h>
#include <cv_bridge/cv_bridge.h>
Expand All @@ -40,10 +40,10 @@
#include <std_srvs/Empty.h>
#include <opencv2/highgui/highgui.hpp>

class MrlIpCamera
class IpCameraDriver
{
public:
explicit MrlIpCamera();
explicit IpCameraDriver();
bool publish();
bool refreshSrvCallback(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res);

Expand Down
2 changes: 1 addition & 1 deletion launch/example.launch
Original file line number Diff line number Diff line change
@@ -1,5 +1,5 @@
<launch>
<node pkg="mrl_ipcamera" type="mrl_ipcamera" name="ipcam" output="screen">
<node pkg="ipcamera_driver" type="ipcamera_driver" name="ipcam" output="screen">
<param name="video_url" type="string" value="rtsp://184.72.239.149/vod/mp4:BigBuckBunny_175k.mov" />
<param name="camera_info_url" type="string" value="package://mrl_ipcamera/launch/example_parameters.yaml" />
<param name="frame_id" type="string" value="cam0_link" />
Expand Down
4 changes: 2 additions & 2 deletions package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<?xml version="1.0"?>
<package>
<name>mrl_ipcamera</name>
<version>2.6.0</version>
<name>ipcamera_driver</name>
<version>0.1.0</version>

<description>
Simple node to publish regular IP camera video streams to a ros topic.
Expand Down
12 changes: 6 additions & 6 deletions src/mrl_ipcamera.cpp → src/ipcamera_driver.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -29,19 +29,19 @@

/* Author: Alireza Hosseini */

#include "mrl_ipcamera/mrl_ipcamera.hpp"
#include "ipcamera_driver/ipcamera_driver.hpp"
#include <sensor_msgs/image_encodings.h>
#include <opencv2/video/video.hpp>

MrlIpCamera::MrlIpCamera() : pnh_("~"), image_transport_(pnh_), camera_info_manager_(pnh_)
IpCameraDriver::IpCameraDriver() : pnh_("~"), image_transport_(pnh_), camera_info_manager_(pnh_)
{
camera_pub_ = image_transport_.advertiseCamera("/camera/image", 10);

pnh_.param<std::string>("video_url", video_url_, "rtsp://admin:A123456789@192.168.1.64/live.sdp?:network-cache=300");
pnh_.getParam("camera_info_url", camera_info_url_);
pnh_.param<std::string>("frame_id", frame_id_, "cam_link");

refresh_service_server_ = pnh_.advertiseService("refresh", &MrlIpCamera::refreshSrvCallback, this);
refresh_service_server_ = pnh_.advertiseService("refresh", &IpCameraDriver::refreshSrvCallback, this);

camera_info_manager_.setCameraName("camera");

Expand All @@ -65,7 +65,7 @@ MrlIpCamera::MrlIpCamera() : pnh_("~"), image_transport_(pnh_), camera_info_mana
cap_.open(video_url_);
}

bool MrlIpCamera::publish()
bool IpCameraDriver::publish()
{
cv::Mat frame;
ros::Rate loop(33);
Expand Down Expand Up @@ -108,7 +108,7 @@ bool MrlIpCamera::publish()
return true;
}

bool MrlIpCamera::refreshSrvCallback(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
bool IpCameraDriver::refreshSrvCallback(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)
{
ROS_INFO("refreshing");
cap_.release();
Expand All @@ -122,7 +122,7 @@ bool MrlIpCamera::refreshSrvCallback(std_srvs::Empty::Request &req, std_srvs::Em
int main(int argc, char **argv)
{
ros::init(argc, argv, "mrl_ip_camera");
MrlIpCamera ipCamera;
IpCameraDriver ipCamera;
ipCamera.publish();
return 0;
}

0 comments on commit e85ad06

Please sign in to comment.