00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #include <cstdio>
00031 #include "tf/transform_broadcaster.h"
00032
00033 class TransformSender
00034 {
00035 public:
00036 ros::NodeHandle node_;
00037
00038 TransformSender(double x, double y, double z, double yaw, double pitch, double roll, ros::Time time, const std::string& frame_id, const std::string& child_frame_id)
00039 {
00040 tf::Quaternion q;
00041 q.setRPY(roll, pitch,yaw);
00042 transform_ = tf::StampedTransform(tf::Transform(q, tf::Vector3(x,y,z)), time, frame_id, child_frame_id );
00043 };
00044 TransformSender(double x, double y, double z, double qx, double qy, double qz, double qw, ros::Time time, const std::string& frame_id, const std::string& child_frame_id) :
00045 transform_(tf::Transform(tf::Quaternion(qx,qy,qz,qw), tf::Vector3(x,y,z)), time, frame_id, child_frame_id){};
00046
00047 ~TransformSender() { }
00048
00049
00050 tf::TransformBroadcaster broadcaster;
00051
00052
00053
00054
00055 void send (ros::Time time) {
00056 transform_.stamp_ = time;
00057 broadcaster.sendTransform(transform_);
00058 };
00059
00060 private:
00061 tf::StampedTransform transform_;
00062
00063 };
00064
00065 int main(int argc, char ** argv)
00066 {
00067
00068 ros::init(argc, argv,"static_transform_publisher", ros::init_options::AnonymousName);
00069
00070 if(argc == 11)
00071 {
00072 ros::Duration sleeper(atof(argv[10])/1000.0);
00073
00074 if (strcmp(argv[8], argv[9]) == 0)
00075 ROS_FATAL("target_frame and source frame are the same (%s, %s) this cannot work", argv[8], argv[9]);
00076
00077 TransformSender tf_sender(atof(argv[1]), atof(argv[2]), atof(argv[3]),
00078 atof(argv[4]), atof(argv[5]), atof(argv[6]), atof(argv[7]),
00079 ros::Time() + sleeper,
00080 argv[8], argv[9]);
00081
00082
00083
00084 while(tf_sender.node_.ok())
00085 {
00086 tf_sender.send(ros::Time::now() + sleeper);
00087 ROS_DEBUG("Sending transform from %s with parent %s\n", argv[8], argv[9]);
00088 sleeper.sleep();
00089 }
00090
00091 return 0;
00092 }
00093 else if (argc == 10)
00094 {
00095 ros::Duration sleeper(atof(argv[9])/1000.0);
00096
00097 if (strcmp(argv[7], argv[8]) == 0)
00098 ROS_FATAL("target_frame and source frame are the same (%s, %s) this cannot work", argv[7], argv[8]);
00099
00100 TransformSender tf_sender(atof(argv[1]), atof(argv[2]), atof(argv[3]),
00101 atof(argv[4]), atof(argv[5]), atof(argv[6]),
00102 ros::Time() + sleeper,
00103 argv[7], argv[8]);
00104
00105
00106
00107 while(tf_sender.node_.ok())
00108 {
00109 tf_sender.send(ros::Time::now() + sleeper);
00110 ROS_DEBUG("Sending transform from %s with parent %s\n", argv[7], argv[8]);
00111 sleeper.sleep();
00112 }
00113
00114 return 0;
00115
00116 }
00117 else
00118 {
00119 printf("A command line utility for manually sending a transform.\n");
00120 printf("It will periodicaly republish the given transform. \n");
00121 printf("Usage: static_transform_publisher x y z yaw pitch roll frame_id child_frame_id period(milliseconds) \n");
00122 printf("OR \n");
00123 printf("Usage: static_transform_publisher x y z qx qy qz qw frame_id child_frame_id period(milliseconds) \n");
00124 printf("\nThis transform is the transform of the coordinate frame from frame_id into the coordinate frame \n");
00125 printf("of the child_frame_id. \n");
00126 ROS_ERROR("static_transform_publisher exited due to not having the right number of arguments");
00127 return -1;
00128 }
00129
00130
00131 };
00132