Skip to content

Commit 551500d

Browse files
author
anurag
committed
Moved namespacing to launch file
1 parent 761ea4c commit 551500d

6 files changed

+11
-9
lines changed

launch/kinect2Client.launch

+2
Original file line numberDiff line numberDiff line change
@@ -1,8 +1,10 @@
11
<launch>
22
<param name="serverNameOrIP" value="172.19.179.53" />
3+
<group ns="/head/kinect2">
34
<node name="startRGB" pkg="k2_client" type="startRGB"/>
45
<node name="startDepth" pkg="k2_client" type="startDepth"/>
56
<node name="startIR" pkg="k2_client" type="startIR"/>
67
<node name="startBody" pkg="k2_client" type="startBody"/>
78
<node name="startAudio" pkg="k2_client" type="startAudio"/>
9+
</group>
810
</launch>

src/startAudio.cpp

+2-2
Original file line numberDiff line numberDiff line change
@@ -27,7 +27,7 @@ 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 = "kinect2/audio";
30+
std::string topicName = "audio";
3131
int twiceStreamSize = 8200;
3232
int streamSize = 4100;
3333

@@ -52,7 +52,7 @@ int main(int argC,char **argV)
5252
bool parsingSuccessful = jsonReader.parse(jsonString,jsonObject,false);
5353
k2_client::Audio audio;
5454
audio.header.stamp = ros::Time(jsonObject["utcTime"].asDouble());
55-
audio.header.frame_id = "/head/kinect2/microphone_frame";
55+
audio.header.frame_id = ros::this_node::getNamespace() + "/microphone_frame";
5656
audio.beamAngle = jsonObject["beamAngle"].asDouble();
5757
audio.beamAngleConfidence = jsonObject["beamAngleConfidence"].asDouble();
5858
for(int i=0;i<256;i++)

src/startBody.cpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -70,7 +70,7 @@ int main(int argC,char **argV)
7070
{
7171
k2_client::Body body;
7272
body.header.stamp = ros::Time(utcTime);
73-
body.header.frame_id = "/head/kinect2/rgb";
73+
body.header.frame_id = ros::this_node::getNamespace() + "/rgb";
7474
body.leanTrackingState = jsonObject[i]["LeanTrackingState"].asInt();
7575
body.lean.leanX = jsonObject[i]["Lean"]["X"].asDouble();
7676
body.lean.leanY = jsonObject[i]["Lean"]["Y"].asDouble();

src/startDepth.cpp

+2-2
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 = "kinect2/depth";
32+
std::string cameraName = "depth";
3333
std::string imageTopicSubName = "image_depth";
3434
std::string cameraInfoSubName = "camera_info";
3535

@@ -56,7 +56,7 @@ int main(int argC,char **argV)
5656
double utcTime;
5757
memcpy(&utcTime,&mySocket.mBuffer[imageSize],sizeof(double));
5858
cvImage.header.stamp = ros::Time(utcTime);
59-
cvImage.header.frame_id = "/head/kinect2/depthFrame";
59+
cvImage.header.frame_id = ros::this_node::getNamespace() + "/depthFrame";
6060
cvImage.encoding = "mono16";
6161
cvImage.image = frame;
6262
cvImage.toImageMsg(rosImage);

src/startIR.cpp

+2-2
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 = "kinect2/ir";
32+
std::string cameraName = "ir";
3333
std::string imageTopicSubName = "image_ir";
3434
std::string cameraInfoSubName = "camera_info";
3535

@@ -56,7 +56,7 @@ int main(int argC,char **argV)
5656
double utcTime;
5757
memcpy(&utcTime,&mySocket.mBuffer[imageSize],sizeof(double));
5858
cvImage.header.stamp = ros::Time(utcTime);
59-
cvImage.header.frame_id = "/head/kinect2/irFrame";
59+
cvImage.header.frame_id = ros::this_node::getNamespace() + "/irFrame";
6060
cvImage.encoding = "mono16";
6161
cvImage.image = frame;
6262
cvImage.toImageMsg(rosImage);

src/startRGB.cpp

+2-2
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 = "kinect2/rgb";
32+
std::string cameraName = "rgb";
3333
std::string imageTopicSubName = "image_color";
3434
std::string cameraInfoSubName = "camera_info";
3535

@@ -56,7 +56,7 @@ int main(int argC,char **argV)
5656
double utcTime;
5757
memcpy(&utcTime,&mySocket.mBuffer[imageSize],sizeof(double));
5858
cvImage.header.stamp = ros::Time(utcTime);
59-
cvImage.header.frame_id = "/head/kinect2/colorFrame";
59+
cvImage.header.frame_id = ros::this_node::getNamespace() + "/colorFrame";
6060
cvImage.encoding = "bgra8";
6161
cvImage.image = frame;
6262
cvImage.toImageMsg(rosImage);

0 commit comments

Comments
 (0)