Skip to content

Commit 761ea4c

Browse files
author
anurag
committed
Changing camera naming to launch file
1 parent 850619e commit 761ea4c

File tree

5 files changed

+16
-16
lines changed

5 files changed

+16
-16
lines changed

src/startAudio.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -27,18 +27,18 @@ WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH
2727
***************************************************************************************/
2828
#include "k2_client.h"
2929

30-
std::string topicName = "/head/kinect2/audio";
30+
std::string topicName = "kinect2/audio";
3131
int twiceStreamSize = 8200;
3232
int streamSize = 4100;
3333

3434
int main(int argC,char **argV)
3535
{
3636
ros::init(argC,argV,"startAudio");
3737
ros::NodeHandle n;
38-
ros::Publisher audioPub = n.advertise<k2_client::Audio>(topicName,1);
3938
std::string serverAddress;
4039
n.getParam("/serverNameOrIP",serverAddress);
4140
Socket mySocket(serverAddress.c_str(),"9004",twiceStreamSize);
41+
ros::Publisher audioPub = n.advertise<k2_client::Audio>(topicName,1);
4242
while(ros::ok())
4343
{
4444
mySocket.readData();

src/startBody.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -28,7 +28,7 @@ WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH
2828
#include "k2_client.h"
2929
#include <iconv.h>
3030

31-
std::string topicName = "/head/kinect2/bodyArray";
31+
std::string topicName = "bodyArray";
3232
size_t streamSize = 56008;
3333
size_t readSkipSize = 56000;
3434
size_t stringSize = 28000;
@@ -37,11 +37,11 @@ int main(int argC,char **argV)
3737
{
3838
ros::init(argC,argV,"startBody");
3939
ros::NodeHandle n;
40-
ros::Publisher bodyPub = n.advertise<k2_client::BodyArray>(topicName,1);
4140
std::string serverAddress;
4241
n.getParam("/serverNameOrIP",serverAddress);
4342
Socket mySocket(serverAddress.c_str(),"9003",streamSize);
4443
iconv_t charConverter = iconv_open("UTF-8","UTF-16");
44+
ros::Publisher bodyPub = n.advertise<k2_client::BodyArray>(topicName,1);
4545
char jsonCharArray[readSkipSize];
4646
while(ros::ok())
4747
{

src/startDepth.cpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -29,7 +29,7 @@ WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH
2929

3030
int imageSize = 434176;
3131
int streamSize = imageSize + sizeof(double);
32-
std::string cameraName = "head/kinect2/depth";
32+
std::string cameraName = "kinect2/depth";
3333
std::string imageTopicSubName = "image_depth";
3434
std::string cameraInfoSubName = "camera_info";
3535

@@ -38,13 +38,13 @@ int main(int argC,char **argV)
3838
ros::init(argC,argV,"startDepth");
3939
ros::NodeHandle n(cameraName);
4040
image_transport::ImageTransport imT(n);
41+
std::string serverAddress;
42+
n.getParam("/serverNameOrIP",serverAddress);
43+
Socket mySocket(serverAddress.c_str(),"9001",streamSize);
4144
image_transport::Publisher imagePublisher = imT.advertise(imageTopicSubName,1);
4245
ros::Publisher cameraInfoPub = n.advertise<sensor_msgs::CameraInfo>(cameraInfoSubName,1);
4346
camera_info_manager::CameraInfoManager camInfoMgr(n,cameraName);
4447
camInfoMgr.loadCameraInfo("");
45-
std::string serverAddress;
46-
n.getParam("/serverNameOrIP",serverAddress);
47-
Socket mySocket(serverAddress.c_str(),"9001",streamSize);
4848
cv::Mat frame;
4949
cv_bridge::CvImage cvImage;
5050
sensor_msgs::Image rosImage;

src/startIR.cpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -29,7 +29,7 @@ WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH
2929

3030
int imageSize = 434176;
3131
int streamSize = imageSize + sizeof(double);
32-
std::string cameraName = "head/kinect2/ir";
32+
std::string cameraName = "kinect2/ir";
3333
std::string imageTopicSubName = "image_ir";
3434
std::string cameraInfoSubName = "camera_info";
3535

@@ -38,13 +38,13 @@ int main(int argC,char **argV)
3838
ros::init(argC,argV,"startIR");
3939
ros::NodeHandle n(cameraName);
4040
image_transport::ImageTransport imT(n);
41+
std::string serverAddress;
42+
n.getParam("/serverNameOrIP",serverAddress);
43+
Socket mySocket(serverAddress.c_str(),"9002",streamSize);
4144
image_transport::Publisher imagePublisher = imT.advertise(imageTopicSubName,1);
4245
ros::Publisher cameraInfoPub = n.advertise<sensor_msgs::CameraInfo>(cameraInfoSubName,1);
4346
camera_info_manager::CameraInfoManager camInfoMgr(n,cameraName);
4447
camInfoMgr.loadCameraInfo("");
45-
std::string serverAddress;
46-
n.getParam("/serverNameOrIP",serverAddress);
47-
Socket mySocket(serverAddress.c_str(),"9002",streamSize);
4848
cv::Mat frame;
4949
cv_bridge::CvImage cvImage;
5050
sensor_msgs::Image rosImage;

src/startRGB.cpp

+4-4
Original file line numberDiff line numberDiff line change
@@ -29,7 +29,7 @@ WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH
2929

3030
int imageSize = 8294400;
3131
int streamSize = imageSize + sizeof(double);
32-
std::string cameraName = "head/kinect2/rgb";
32+
std::string cameraName = "kinect2/rgb";
3333
std::string imageTopicSubName = "image_color";
3434
std::string cameraInfoSubName = "camera_info";
3535

@@ -38,13 +38,13 @@ int main(int argC,char **argV)
3838
ros::init(argC,argV,"startRGB");
3939
ros::NodeHandle n(cameraName);
4040
image_transport::ImageTransport imT(n);
41+
std::string serverAddress;
42+
n.getParam("/serverNameOrIP",serverAddress);
43+
Socket mySocket(serverAddress.c_str(),"9000",streamSize);
4144
image_transport::Publisher imagePublisher = imT.advertise(imageTopicSubName,1);
4245
ros::Publisher cameraInfoPub = n.advertise<sensor_msgs::CameraInfo>(cameraInfoSubName,1);
4346
camera_info_manager::CameraInfoManager camInfoMgr(n,cameraName);
4447
camInfoMgr.loadCameraInfo("");
45-
std::string serverAddress;
46-
n.getParam("/serverNameOrIP",serverAddress);
47-
Socket mySocket(serverAddress.c_str(),"9000",streamSize);
4848
cv::Mat frame;
4949
cv_bridge::CvImage cvImage;
5050
sensor_msgs::Image rosImage;

0 commit comments

Comments
 (0)