00001 /* 00002 * Copyright (c) 2008, Willow Garage, Inc. 00003 * All rights reserved. 00004 * 00005 * Redistribution and use in source and binary forms, with or without 00006 * modification, are permitted provided that the following conditions are met: 00007 * 00008 * * Redistributions of source code must retain the above copyright 00009 * notice, this list of conditions and the following disclaimer. 00010 * * Redistributions in binary form must reproduce the above copyright 00011 * notice, this list of conditions and the following disclaimer in the 00012 * documentation and/or other materials provided with the distribution. 00013 * * Neither the name of the Willow Garage, Inc. nor the names of its 00014 * contributors may be used to endorse or promote products derived from 00015 * this software without specific prior written permission. 00016 * 00017 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 00018 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 00019 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE 00020 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE 00021 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 00022 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 00023 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 00024 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 00025 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 00026 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00027 * POSSIBILITY OF SUCH DAMAGE. 00028 */ 00029 00030 #include <cstdio> 00031 #include "tf2_ros/static_transform_broadcaster.h" 00032 00033 int main(int argc, char ** argv) 00034 { 00035 //Initialize ROS 00036 ros::init(argc, argv,"static_transform_publisher", ros::init_options::AnonymousName); 00037 tf2::StaticTransformBroadcaster broadcaaster; 00038 00039 if(argc == 10) 00040 { 00041 00042 if (strcmp(argv[8], argv[9]) == 0) 00043 { 00044 ROS_FATAL("target_frame and source frame are the same (%s, %s) this cannot work", argv[8], argv[9]); 00045 return 1; 00046 } 00047 00048 geometry_msgs::TransformStamped msg; 00049 msg.transform.translation.x = atof(argv[1]); 00050 msg.transform.translation.y = atof(argv[2]); 00051 msg.transform.translation.z = atof(argv[3]); 00052 msg.transform.rotation.x = atof(argv[4]); 00053 msg.transform.rotation.y = atof(argv[5]); 00054 msg.transform.rotation.z = atof(argv[6]); 00055 msg.transform.rotation.w = atof(argv[7]); 00056 msg.header.stamp = ros::Time::now(); 00057 msg.header.frame_id = argv[8]; 00058 msg.child_frame_id = argv[9]; 00059 00060 00061 00062 broadcaaster.sendTransform(msg); 00063 ROS_INFO("Spinning until killed publishing %s to %s", msg.header.frame_id.c_str(), msg.child_frame_id.c_str()); 00064 ros::spin(); 00065 00066 return 0; 00067 } 00068 /* else if (argc == 10) 00069 { 00070 ros::Duration sleeper(atof(argv[9])/1000.0); 00071 00072 if (strcmp(argv[7], argv[8]) == 0) 00073 ROS_FATAL("target_frame and source frame are the same (%s, %s) this cannot work", argv[7], argv[8]); 00074 00075 TransformSender tf_sender(atof(argv[1]), atof(argv[2]), atof(argv[3]), 00076 atof(argv[4]), atof(argv[5]), atof(argv[6]), 00077 ros::Time() + sleeper, //Future dating to allow slower sending w/o timeout 00078 argv[7], argv[8]); 00079 00080 00081 00082 while(tf_sender.node_.ok()) 00083 { 00084 tf_sender.send(ros::Time::now() + sleeper); 00085 ROS_DEBUG("Sending transform from %s with parent %s\n", argv[7], argv[8]); 00086 sleeper.sleep(); 00087 } 00088 return 0; 00089 00090 }*/ 00091 else 00092 { 00093 printf("A command line utility for manually sending a transform.\n"); 00094 printf("It will periodicaly republish the given transform. \n"); 00095 printf("Usage: static_transform_publisher x y z yaw pitch roll frame_id child_frame_id \n"); 00096 //printf("OR \n"); 00097 //printf("Usage: static_transform_publisher x y z qx qy qz qw frame_id child_frame_id \n"); 00098 printf("\nThis transform is the transform of the coordinate frame from frame_id into the coordinate frame \n"); 00099 printf("of the child_frame_id. \n"); 00100 ROS_ERROR("static_transform_publisher exited due to not having the right number of arguments"); 00101 return -1; 00102 } 00103 00104 00105 }; 00106