31 #include <Eigen/Geometry>    33 #include <boost/program_options.hpp>    34 namespace po = boost::program_options;
    36 static void usage(
const char* prog_name, 
const po::options_description& opts, 
bool desc = 
false) {
    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;
    41   std::cout << std::endl;
    42   std::cout << 
"Usage: " << prog_name << 
" [options] x y z  <rotation> parent_frame_id child_frame_id"    44   std::cout << opts << std::endl;
    47 static void parse_arguments(
int argc, 
char** argv, geometry_msgs::TransformStamped& msg) {
    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));
    53   po::variables_map variables_map;
    54   std::vector<std::string> 
args;
    55   std::vector<std::string>::const_iterator arg;
    57     po::parsed_options parsed =
    58         po::command_line_parser(argc, argv).options(options_description).allow_unregistered().run();
    60     po::store(parsed, variables_map);
    61     po::notify(variables_map);
    62     args = po::collect_unrecognized(parsed.options, po::include_positional);
    65     if (variables_map.count(
"help")) {
    66       usage(argv[0], options_description, 
true);
    69     const size_t numArgs = 3 + 2;
    71     bool bQuatMode = (mode == 
"wxyz" || mode == 
"xyzw");
    73       if (args.size() == numArgs + 4) {
    76       } 
else if (args.size() == numArgs + 3) {
    79         throw po::error(
"invalid number of positional arguments");
    84     msg.transform.translation.x = boost::lexical_cast<
double>(*arg);
    86     msg.transform.translation.y = boost::lexical_cast<
double>(*arg);
    88     msg.transform.translation.z = boost::lexical_cast<
double>(*arg);
    94       if (args.size() != numArgs + 4)
    95         throw po::error(
"quaternion mode requires " + boost::lexical_cast<std::string>(numArgs + 4) +
    96                         " positional arguments");
    98       const std::string eigen_order(
"xyzw");
   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);
   105       q = Eigen::Quaterniond(data);
   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)");
   114       const std::string axes_order(
"xyz");
   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]));
   124         angles[i] = boost::lexical_cast<
double>(*arg);
   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]));
   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();
   139     msg.header.frame_id = *arg++;
   140     msg.child_frame_id = *arg++;
   141   } 
catch (
const po::error& e) {
   143     usage(argv[0], options_description);
   145   } 
catch (
const boost::bad_lexical_cast& e) {
   147     usage(argv[0], options_description);
   152 int main(
int argc, 
char** argv) {
   156   geometry_msgs::TransformStamped msg;
   159   if (msg.header.frame_id.empty() || msg.child_frame_id.empty()) {
   160     ROS_FATAL(
"target or source frame is empty");
   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());
   172   ROS_INFO(
"Spinning until killed, publishing %s to %s", msg.header.frame_id.c_str(),
   173            msg.child_frame_id.c_str());
 
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ROSCPP_DECL void spin(Spinner &spinner)
#define ROS_FATAL_STREAM(args)