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 #include <ros/ros.h>
00037 #include <geometry_msgs/PoseStamped.h>
00038 #include <eigen_conversions/eigen_msg.h>
00039
00040 namespace jsk_topic_tools
00041 {
00042 class PoseStampedTransformer
00043 {
00044 public:
00045 typedef boost::shared_ptr<PoseStampedTransformer> Ptr;
00046 PoseStampedTransformer(double x, double y, double z,
00047 double yaw, double pitch, double roll,
00048 std::string from_topic,
00049 std::string to_topic);
00050 virtual ~PoseStampedTransformer();
00051 protected:
00052 void transform(const geometry_msgs::PoseStamped::ConstPtr& pose_msg);
00053 ros::Subscriber sub_;
00054 ros::Publisher pub_;
00055 double x_;
00056 double y_;
00057 double z_;
00058 double roll_;
00059 double pitch_;
00060 double yaw_;
00061 private:
00062
00063 };
00064
00065 PoseStampedTransformer::PoseStampedTransformer(
00066 double x, double y, double z,
00067 double yaw, double pitch, double roll,
00068 std::string from_topic, std::string to_topic):
00069 x_(x), y_(y), z_(z), yaw_(yaw), pitch_(pitch), roll_(roll)
00070 {
00071 ros::NodeHandle nh;
00072 pub_ = nh.advertise<geometry_msgs::PoseStamped>(
00073 to_topic, 1);
00074 sub_ = nh.subscribe(from_topic, 1,
00075 &PoseStampedTransformer::transform, this);
00076 }
00077
00078 PoseStampedTransformer::~PoseStampedTransformer()
00079 {
00080
00081 }
00082
00083 void PoseStampedTransformer::transform(
00084 const geometry_msgs::PoseStamped::ConstPtr& pose_msg)
00085 {
00086 Eigen::Affine3d input_transform;
00087 tf::poseMsgToEigen(pose_msg->pose, input_transform);
00088 Eigen::AngleAxisd roll_angle(roll_, Eigen::Vector3d::UnitZ());
00089 Eigen::AngleAxisd yaw_angle(yaw_, Eigen::Vector3d::UnitY());
00090 Eigen::AngleAxisd pitch_angle(pitch_, Eigen::Vector3d::UnitX());
00091
00092 Eigen::Affine3d transformation
00093 = Eigen::Translation3d(x_, y_, z_) * roll_angle * yaw_angle * pitch_angle;
00094 Eigen::Affine3d output_transform = input_transform * transformation;
00095 geometry_msgs::PoseStamped output_pose_msg;
00096 tf::poseEigenToMsg(output_transform, output_pose_msg.pose);
00097 output_pose_msg.header = pose_msg->header;
00098 pub_.publish(output_pose_msg);
00099 }
00100
00101 }
00102
00103 int usage(char** argv)
00104 {
00105 std::cerr << "Usage:: " << argv[0]
00106 << " x y z yaw pitch roll from_topic to_topic"
00107 << std::endl;
00108 }
00109
00110 int main(int argc, char** argv)
00111 {
00112 ros::init(argc, argv, "static_transform_pose_stamped",
00113 ros::init_options::AnonymousName);
00114
00115 if (argc != 9) {
00116 usage(argv);
00117 exit(1);
00118 }
00119
00120 jsk_topic_tools::PoseStampedTransformer p(::atof(argv[1]),
00121 ::atof(argv[2]),
00122 ::atof(argv[3]),
00123 ::atof(argv[4]),
00124 ::atof(argv[5]),
00125 ::atof(argv[6]),
00126 argv[7],
00127 argv[8]);
00128 ros::spin();
00129 }