Go to the documentation of this file.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
00031
00032
00033
00034
00035
00036
00037 #include <ros/ros.h>
00038 #include <tf/transform_broadcaster.h>
00039 #include <math.h>
00040
00041 #define SONAR_RADIUS 0.125
00042
00043 int main(int argc, char** argv)
00044 {
00045 ros::init(argc, argv, "roomba_tf_setup");
00046 ros::NodeHandle n;
00047
00048 ros::Rate r(50);
00049
00050 tf::TransformBroadcaster broadcaster;
00051
00052 while(n.ok())
00053 {
00054 broadcaster.sendTransform(tf::StampedTransform(tf::Transform(tf::createQuaternionFromYaw(M_PI/2.0), tf::Vector3(SONAR_RADIUS*cos(M_PI/2.0), SONAR_RADIUS*sin(M_PI/2.0), 0.120)),
00055 ros::Time::now(),"base_link", "/base_sonar_0"));
00056
00057 broadcaster.sendTransform(tf::StampedTransform(tf::Transform(tf::createQuaternionFromYaw(M_PI/4.0), tf::Vector3(SONAR_RADIUS*cos(M_PI/4.0), SONAR_RADIUS*sin(M_PI/4.0), 0.120)),
00058 ros::Time::now(),"base_link", "/base_sonar_1"));
00059
00060 broadcaster.sendTransform(tf::StampedTransform(tf::Transform(tf::createQuaternionFromYaw(0.0), tf::Vector3(SONAR_RADIUS, 0.000, 0.120)),
00061 ros::Time::now(),"base_link", "/base_sonar_2"));
00062
00063 broadcaster.sendTransform(tf::StampedTransform(tf::Transform(tf::createQuaternionFromYaw(-M_PI/4.0), tf::Vector3(SONAR_RADIUS*cos(-M_PI/4.0), SONAR_RADIUS*sin(-M_PI/4.0), 0.120)),
00064 ros::Time::now(),"base_link", "/base_sonar_3"));
00065
00066 broadcaster.sendTransform(tf::StampedTransform(tf::Transform(tf::createQuaternionFromYaw(-M_PI/2.0), tf::Vector3(SONAR_RADIUS*cos(-M_PI/2.0), SONAR_RADIUS*sin(-M_PI/2.0), 0.120)),
00067 ros::Time::now(),"base_link", "/base_sonar_4"));
00068
00069 r.sleep();
00070 }
00071 }