/
static_transform_broadcaster_program.cpp
118 lines (101 loc) · 4.6 KB
/
static_transform_broadcaster_program.cpp
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
/*
* Copyright (c) 2008, Willow Garage, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* * Neither the name of the Willow Garage, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from
* this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/
#include <math.h>
#include <cstdio>
#include "tf2_ros/static_transform_broadcaster.h"
int main(int argc, char ** argv)
{
//Initialize ROS
ros::init(argc, argv,"static_transform_publisher", ros::init_options::AnonymousName);
tf2_ros::StaticTransformBroadcaster broadcaaster;
if(argc == 10)
{
if (strcmp(argv[8], argv[9]) == 0)
{
ROS_FATAL("target_frame and source frame are the same (%s, %s) this cannot work", argv[8], argv[9]);
return 1;
}
geometry_msgs::TransformStamped msg;
msg.transform.translation.x = atof(argv[1]);
msg.transform.translation.y = atof(argv[2]);
msg.transform.translation.z = atof(argv[3]);
msg.transform.rotation.x = atof(argv[4]);
msg.transform.rotation.y = atof(argv[5]);
msg.transform.rotation.z = atof(argv[6]);
msg.transform.rotation.w = atof(argv[7]);
msg.header.stamp = ros::Time::now();
msg.header.frame_id = argv[8];
msg.child_frame_id = argv[9];
broadcaaster.sendTransform(msg);
ROS_INFO("Spinning until killed publishing %s to %s", msg.header.frame_id.c_str(), msg.child_frame_id.c_str());
ros::spin();
return 0;
}
else if (argc == 9)
{
if (strcmp(argv[7], argv[8]) == 0)
{
ROS_FATAL("target_frame and source frame are the same (%s, %s) this cannot work", argv[8], argv[9]);
return 1;
}
geometry_msgs::TransformStamped msg;
msg.transform.translation.x = atof(argv[1]);
msg.transform.translation.y = atof(argv[2]);
msg.transform.translation.z = atof(argv[3]);
double halfYaw = atof(argv[4]) * 0.5;
double halfPitch = atof(argv[5]) * 0.5;
double halfRoll = atof(argv[6]) * 0.5;
double cosYaw = cos(halfYaw);
double sinYaw = sin(halfYaw);
double cosPitch = cos(halfPitch);
double sinPitch = sin(halfPitch);
double cosRoll = cos(halfRoll);
double sinRoll = sin(halfRoll);
msg.transform.rotation.x = sinRoll * cosPitch * cosYaw - cosRoll * sinPitch * sinYaw;
msg.transform.rotation.y = cosRoll * sinPitch * cosYaw + sinRoll * cosPitch * sinYaw;
msg.transform.rotation.z = cosRoll * cosPitch * sinYaw - sinRoll * sinPitch * cosYaw;
msg.transform.rotation.w = cosRoll * cosPitch * cosYaw + sinRoll * sinPitch * sinYaw;
broadcaaster.sendTransform(msg);
ROS_INFO("Spinning until killed publishing %s to %s", msg.header.frame_id.c_str(), msg.child_frame_id.c_str());
ros::spin();
return 0;
}
else
{
printf("A command line utility for manually sending a transform.\n");
//printf("It will periodicaly republish the given transform. \n");
printf("Usage: static_transform_publisher x y z qx qy qz qw frame_id child_frame_id \n");
printf("OR \n");
printf("Usage: static_transform_publisher x y z yaw pitch roll frame_id child_frame_id \n");
printf("\nThis transform is the transform of the coordinate frame from frame_id into the coordinate frame \n");
printf("of the child_frame_id. \n");
ROS_ERROR("static_transform_publisher exited due to not having the right number of arguments");
return -1;
}
};