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
00038
00039 #include <ros/ros.h>
00040 #include <geometry_msgs/PoseWithCovarianceStamped.h>
00041 #include <kdl/frames.hpp>
00042
00043 int main(int argc, char** argv)
00044 {
00045 ros::init(argc, argv, "detector_stub");
00046 double x, y, z, Rx, Ry, Rz;
00047 std::string frame_id;
00048 ros::NodeHandle node("~");
00049 node.param("x", x, 0.0);
00050 node.param("y", y, 0.0);
00051 node.param("z", z, 0.0);
00052 node.param("Rx", Rx, 0.0);
00053 node.param("Ry", Ry, 0.0);
00054 node.param("Rz", Rz, 0.0);
00055 node.param("frame_id", frame_id, std::string("frame_id_not_specified"));
00056
00057 ros::NodeHandle node_top;
00058 ros::Publisher pub_pose = node_top.advertise<geometry_msgs::PoseWithCovarianceStamped>("pose", 10);
00059 geometry_msgs::PoseWithCovarianceStamped pose;
00060 pose.header.frame_id = frame_id;
00061 pose.pose.pose.position.x = x;
00062 pose.pose.pose.position.y = y;
00063 pose.pose.pose.position.z = z;
00064 KDL::Rotation tmp = KDL::Rotation::RPY(Rx, Ry, Rz);
00065 double Qx, Qy, Qz, Qw;
00066 tmp.GetQuaternion(Qx, Qy, Qz, Qw);
00067 pose.pose.pose.orientation.x = Qx;
00068 pose.pose.pose.orientation.y = Qy;
00069 pose.pose.pose.orientation.z = Qz;
00070 pose.pose.pose.orientation.w = Qw;
00071
00072 double cov[36] = {0.0001, 0, 0, 0, 0, 0,
00073 0, 0.0001, 0, 0, 0, 0,
00074 0, 0, 0.0001, 0, 0, 0,
00075 0, 0, 0, 0.0001, 0, 0,
00076 0, 0, 0, 0, 0.0001, 0,
00077 0, 0, 0, 0, 0, 0.0001};
00078 for (unsigned int i=0; i<36; i++)
00079 pose.pose.covariance[i] = cov[i];
00080
00081 while (ros::ok()){
00082 pose.header.stamp = ros::Time::now();
00083 pub_pose.publish(pose);
00084 ros::Duration(0.4).sleep();
00085 }
00086 return 0;
00087 }