static_transform_broadcaster_program.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2008, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
31 #include <Eigen/Geometry>
32 
33 #include <boost/program_options.hpp>
34 namespace po = boost::program_options;
35 
36 static void usage(const char* prog_name, const po::options_description& opts, bool desc = false) {
37  if (desc) {
38  std::cout << "A command line utility for manually defining a (static) transform" << std::endl;
39  std::cout << "from parent_frame_id to child_frame_id." << std::endl;
40  }
41  std::cout << std::endl;
42  std::cout << "Usage: " << prog_name << " [options] x y z <rotation> parent_frame_id child_frame_id"
43  << std::endl;
44  std::cout << opts << std::endl;
45 }
46 
47 static void parse_arguments(int argc, char** argv, geometry_msgs::TransformStamped& msg) {
48  std::string mode;
49  po::options_description options_description("allowed options");
50  options_description.add_options()("help,h", "show this help message")("mode,m",
51  po::value<std::string>(&mode));
52 
53  po::variables_map variables_map;
54  std::vector<std::string> args;
55  std::vector<std::string>::const_iterator arg;
56  try {
57  po::parsed_options parsed =
58  po::command_line_parser(argc, argv).options(options_description).allow_unregistered().run();
59 
60  po::store(parsed, variables_map);
61  po::notify(variables_map);
62  args = po::collect_unrecognized(parsed.options, po::include_positional);
63  arg = args.begin();
64 
65  if (variables_map.count("help")) {
66  usage(argv[0], options_description, true);
67  exit(EXIT_SUCCESS);
68  }
69  const size_t numArgs = 3 + 2;
70 
71  bool bQuatMode = (mode == "wxyz" || mode == "xyzw");
72  if (mode.empty()) {
73  if (args.size() == numArgs + 4) {
74  bQuatMode = true; // 4 rotational args trigger quaternion mode too
75  mode = "xyzw";
76  } else if (args.size() == numArgs + 3) {
77  mode = "zyx";
78  } else {
79  throw po::error("invalid number of positional arguments");
80  }
81  }
82 
83  // consume position arguments
84  msg.transform.translation.x = boost::lexical_cast<double>(*arg);
85  ++arg;
86  msg.transform.translation.y = boost::lexical_cast<double>(*arg);
87  ++arg;
88  msg.transform.translation.z = boost::lexical_cast<double>(*arg);
89  ++arg;
90 
91  // consume orientation arguments
92  Eigen::Quaterniond q;
93  if (bQuatMode) { // parse Quaternion
94  if (args.size() != numArgs + 4)
95  throw po::error("quaternion mode requires " + boost::lexical_cast<std::string>(numArgs + 4) +
96  " positional arguments");
97 
98  const std::string eigen_order("xyzw");
99  double data[4];
100  for (size_t i = 0; i < 4; ++i) {
101  size_t idx = eigen_order.find(mode[i]);
102  data[idx] = boost::lexical_cast<double>(*arg);
103  ++arg;
104  }
105  q = Eigen::Quaterniond(data);
106 
107  } else { // parse Euler angles
108  if (args.size() != numArgs + 3)
109  throw po::error("Euler angles require " + boost::lexical_cast<std::string>(numArgs + 3) +
110  " positional arguments");
111  if (mode.size() != 3)
112  throw po::error("mode specification for Euler angles requires a string from 3 chars (xyz)");
113 
114  const std::string axes_order("xyz");
115  size_t axes_idxs[3];
116  double angles[3];
117 
118  for (size_t i = 0; i < 3; ++i) {
119  size_t idx = axes_order.find(mode[i]);
120  if (idx == std::string::npos)
121  throw po::error("invalid axis specification for Euler angles: " +
122  boost::lexical_cast<std::string>(mode[i]));
123  axes_idxs[i] = idx;
124  angles[i] = boost::lexical_cast<double>(*arg);
125  ++arg;
126  }
127  q = Eigen::AngleAxisd(angles[0], Eigen::Vector3d::Unit(axes_idxs[0])) *
128  Eigen::AngleAxisd(angles[1], Eigen::Vector3d::Unit(axes_idxs[1])) *
129  Eigen::AngleAxisd(angles[2], Eigen::Vector3d::Unit(axes_idxs[2]));
130  }
131  // assign quaternion
132  q.normalize();
133  msg.transform.rotation.x = q.x();
134  msg.transform.rotation.y = q.y();
135  msg.transform.rotation.z = q.z();
136  msg.transform.rotation.w = q.w();
137 
138  // consume link arguments
139  msg.header.frame_id = *arg++;
140  msg.child_frame_id = *arg++;
141  } catch (const po::error& e) {
142  ROS_FATAL_STREAM(e.what());
143  usage(argv[0], options_description);
144  exit(EXIT_FAILURE);
145  } catch (const boost::bad_lexical_cast& e) {
146  ROS_FATAL_STREAM("failed to parse numerical value: " << *arg);
147  usage(argv[0], options_description);
148  exit(EXIT_FAILURE);
149  }
150 }
151 
152 int main(int argc, char** argv) {
153  // Initialize ROS
154  ros::init(argc, argv, "static_transform_publisher", ros::init_options::AnonymousName);
155 
156  geometry_msgs::TransformStamped msg;
157  parse_arguments(argc, argv, msg);
158 
159  if (msg.header.frame_id.empty() || msg.child_frame_id.empty()) {
160  ROS_FATAL("target or source frame is empty");
161  exit(1);
162  }
163  if (msg.header.frame_id == msg.child_frame_id) {
164  ROS_FATAL("target and source frame are the same (%s, %s) this cannot work",
165  msg.child_frame_id.c_str(), msg.header.frame_id.c_str());
166  exit(1);
167  }
168 
170  broadcaster.sendTransform(msg);
171 
172  ROS_INFO("Spinning until killed, publishing %s to %s", msg.header.frame_id.c_str(),
173  msg.child_frame_id.c_str());
174  ros::spin();
175 
176  return 0;
177 }
#define ROS_FATAL(...)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
int main(int argc, char **argv)
ROSCPP_DECL void spin(Spinner &spinner)
#define ROS_FATAL_STREAM(args)
#define ROS_INFO(...)
static void usage(const char *prog_name, const po::options_description &opts, bool desc=false)
void sendTransform(const geometry_msgs::TransformStamped &transform)
static void parse_arguments(int argc, char **argv, geometry_msgs::TransformStamped &msg)


agni_tf_tools
Author(s): Robert Haschke
autogenerated on Tue Apr 13 2021 02:29:55